├── C-LOAM ├── CMakeLists.txt ├── include │ ├── KDTreeVectorOfVectorsAdaptor.h │ ├── Scancontext.h │ ├── nanoflann.hpp │ ├── tictoc.h │ └── util.h ├── launch │ ├── run.launch │ └── test.rviz ├── package.xml └── src │ ├── Scancontext.cpp │ ├── ceresFactor.hpp │ ├── featureAssociation.cpp │ ├── imageProjection.cpp │ ├── mapOptmization.cpp │ └── transformFusion.cpp ├── Gemfile ├── README.md ├── cloud_msgs ├── CMakeLists.txt ├── msg │ └── cloud_info.msg └── package.xml ├── index.html ├── run_server.sh └── web ├── resources ├── C-LOAM.gif ├── ablation.png ├── dynamic_removal.png ├── ground_extraction.png ├── localization.png ├── loop_closure.png └── pipeline.png └── static ├── css ├── bootstrap-4.4.1.css ├── bulma-carousel.min.css ├── bulma-slider.min.css ├── bulma.css.map.txt ├── bulma.min.css ├── dics.original.css ├── fontawesome.all.min.css ├── index.css └── style.css ├── images ├── logo.png └── logo.webp └── js ├── app.js ├── bulma-carousel.js ├── bulma-carousel.min.js ├── bulma-slider.js ├── bulma-slider.min.js ├── dics.original.js ├── event_handler.js ├── fontawesome.all.min.js ├── index.js └── video_comparison.js /C-LOAM/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(c_loam) 3 | 4 | #set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -O3") 5 | set(CMAKE_CXX_STANDARD 14) 6 | 7 | find_package(catkin REQUIRED COMPONENTS 8 | tf 9 | roscpp 10 | rospy 11 | cv_bridge 12 | image_transport 13 | 14 | pcl_ros 15 | pcl_conversions 16 | 17 | std_msgs 18 | sensor_msgs 19 | geometry_msgs 20 | nav_msgs 21 | cloud_msgs 22 | 23 | cv_bridge 24 | image_transport 25 | ) 26 | 27 | find_package (Eigen3 3.3 REQUIRED NO_MODULE) 28 | ##set(GTSAM_DIR "/home/jyp/3rdparty/gtsam-4.0.3/build") #4.0.3 29 | find_package(GTSAM REQUIRED QUIET) 30 | find_package(PCL REQUIRED QUIET) 31 | find_package(OpenCV REQUIRED QUIET) 32 | find_package(Ceres REQUIRED) 33 | 34 | 35 | catkin_package( 36 | INCLUDE_DIRS include 37 | CATKIN_DEPENDS cloud_msgs 38 | DEPENDS PCL 39 | ) 40 | 41 | include_directories( 42 | include 43 | ${catkin_INCLUDE_DIRS} 44 | ${PCL_INCLUDE_DIRS} 45 | ${OpenCV_INCLUDE_DIRS} 46 | ${GTSAM_INCLUDE_DIR} 47 | ${CERES_INCLUDE_DIRS} 48 | ) 49 | 50 | link_directories( 51 | include 52 | ${OpenCV_LIBRARY_DIRS} 53 | ${PCL_LIBRARY_DIRS} 54 | ${GTSAM_LIBRARY_DIRS} 55 | ${CERES_LIBRARIES} 56 | ) 57 | 58 | add_executable(imageProjection src/imageProjection.cpp) 59 | add_dependencies(imageProjection ${catkin_EXPORTED_TARGETS} cloud_msgs_gencpp) 60 | target_link_libraries(imageProjection ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES}) 61 | 62 | add_executable(featureAssociation src/featureAssociation.cpp) 63 | add_dependencies(featureAssociation ${catkin_EXPORTED_TARGETS} cloud_msgs_gencpp) 64 | target_link_libraries(featureAssociation ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES}) 65 | 66 | add_executable(mapOptmization 67 | src/mapOptmization.cpp 68 | src/Scancontext.cpp 69 | ) 70 | target_link_libraries(mapOptmization 71 | ${catkin_LIBRARIES} 72 | ${PCL_LIBRARIES} 73 | ${OpenCV_LIBRARIES} 74 | ${CERES_LIBRARIES} 75 | gtsam 76 | Eigen3::Eigen 77 | ) 78 | 79 | add_executable(transformFusion src/transformFusion.cpp) 80 | target_link_libraries(transformFusion ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES}) 81 | -------------------------------------------------------------------------------- /C-LOAM/include/KDTreeVectorOfVectorsAdaptor.h: -------------------------------------------------------------------------------- 1 | /*********************************************************************** 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright 2011-16 Jose Luis Blanco (joseluisblancoc@gmail.com). 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * 1. Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * 2. Redistributions in binary form must reproduce the above copyright 14 | * notice, this list of conditions and the following disclaimer in the 15 | * documentation and/or other materials provided with the distribution. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR 18 | * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES 19 | * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. 20 | * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, 21 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT 22 | * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 23 | * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY 24 | * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 25 | * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF 26 | * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 27 | *************************************************************************/ 28 | 29 | #pragma once 30 | 31 | #include 32 | 33 | #include 34 | 35 | // ===== This example shows how to use nanoflann with these types of containers: ======= 36 | //typedef std::vector > my_vector_of_vectors_t; 37 | //typedef std::vector my_vector_of_vectors_t; // This requires #include 38 | // ===================================================================================== 39 | 40 | 41 | /** A simple vector-of-vectors adaptor for nanoflann, without duplicating the storage. 42 | * The i'th vector represents a point in the state space. 43 | * 44 | * \tparam DIM If set to >0, it specifies a compile-time fixed dimensionality for the points in the data set, allowing more compiler optimizations. 45 | * \tparam num_t The type of the point coordinates (typically, double or float). 46 | * \tparam Distance The distance metric to use: nanoflann::metric_L1, nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. 47 | * \tparam IndexType The type for indices in the KD-tree index (typically, size_t of int) 48 | */ 49 | template 50 | struct KDTreeVectorOfVectorsAdaptor 51 | { 52 | typedef KDTreeVectorOfVectorsAdaptor self_t; 53 | typedef typename Distance::template traits::distance_t metric_t; 54 | typedef nanoflann::KDTreeSingleIndexAdaptor< metric_t,self_t,DIM,IndexType> index_t; 55 | 56 | index_t* index; //! The kd-tree index for the user to call its methods as usual with any other FLANN index. 57 | 58 | /// Constructor: takes a const ref to the vector of vectors object with the data points 59 | KDTreeVectorOfVectorsAdaptor(const size_t /* dimensionality */, const VectorOfVectorsType &mat, const int leaf_max_size = 10) : m_data(mat) 60 | { 61 | assert(mat.size() != 0 && mat[0].size() != 0); 62 | const size_t dims = mat[0].size(); 63 | if (DIM>0 && static_cast(dims) != DIM) 64 | throw std::runtime_error("Data set dimensionality does not match the 'DIM' template argument"); 65 | index = new index_t( static_cast(dims), *this /* adaptor */, nanoflann::KDTreeSingleIndexAdaptorParams(leaf_max_size ) ); 66 | index->buildIndex(); 67 | } 68 | 69 | ~KDTreeVectorOfVectorsAdaptor() { 70 | delete index; 71 | } 72 | 73 | const VectorOfVectorsType &m_data; 74 | 75 | /** Query for the \a num_closest closest points to a given point (entered as query_point[0:dim-1]). 76 | * Note that this is a short-cut method for index->findNeighbors(). 77 | * The user can also call index->... methods as desired. 78 | * \note nChecks_IGNORED is ignored but kept for compatibility with the original FLANN interface. 79 | */ 80 | inline void query(const num_t *query_point, const size_t num_closest, IndexType *out_indices, num_t *out_distances_sq, const int nChecks_IGNORED = 10) const 81 | { 82 | nanoflann::KNNResultSet resultSet(num_closest); 83 | resultSet.init(out_indices, out_distances_sq); 84 | index->findNeighbors(resultSet, query_point, nanoflann::SearchParams()); 85 | } 86 | 87 | /** @name Interface expected by KDTreeSingleIndexAdaptor 88 | * @{ */ 89 | 90 | const self_t & derived() const { 91 | return *this; 92 | } 93 | self_t & derived() { 94 | return *this; 95 | } 96 | 97 | // Must return the number of data points 98 | inline size_t kdtree_get_point_count() const { 99 | return m_data.size(); 100 | } 101 | 102 | // Returns the dim'th component of the idx'th point in the class: 103 | inline num_t kdtree_get_pt(const size_t idx, const size_t dim) const { 104 | return m_data[idx][dim]; 105 | } 106 | 107 | // Optional bounding-box computation: return false to default to a standard bbox computation loop. 108 | // Return true if the BBOX was already computed by the class and returned in "bb" so it can be avoided to redo it again. 109 | // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3 for point clouds) 110 | template 111 | bool kdtree_get_bbox(BBOX & /*bb*/) const { 112 | return false; 113 | } 114 | 115 | /** @} */ 116 | 117 | }; // end of KDTreeVectorOfVectorsAdaptor 118 | -------------------------------------------------------------------------------- /C-LOAM/include/Scancontext.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | 13 | #include 14 | 15 | #include 16 | #include 17 | #include 18 | #include 19 | 20 | #include 21 | #include 22 | #include 23 | #include 24 | 25 | #include "nanoflann.hpp" 26 | #include "KDTreeVectorOfVectorsAdaptor.h" 27 | 28 | #include "tictoc.h" 29 | 30 | using namespace Eigen; 31 | using namespace nanoflann; 32 | 33 | using std::cout; 34 | using std::endl; 35 | using std::make_pair; 36 | 37 | using std::atan2; 38 | using std::cos; 39 | using std::sin; 40 | 41 | using SCPointType = pcl::PointXYZI; // using xyz only. but a user can exchange the original bin encoding function (i.e., max hegiht) to max intensity (for detail, refer 20 ICRA Intensity Scan Context) 42 | using KeyMat = std::vector >; 43 | using InvKeyTree = KDTreeVectorOfVectorsAdaptor< KeyMat, float >; 44 | 45 | 46 | // namespace SC2 47 | // { 48 | 49 | void coreImportTest ( void ); 50 | 51 | 52 | // sc param-independent helper functions 53 | float xy2theta( const float & _x, const float & _y ); 54 | MatrixXd circshift( MatrixXd &_mat, int _num_shift ); 55 | std::vector eig2stdvec( MatrixXd _eigmat ); 56 | 57 | 58 | class SCManager 59 | { 60 | public: 61 | SCManager( ) = default; // reserving data space (of std::vector) could be considered. but the descriptor is lightweight so don't care. 62 | 63 | Eigen::MatrixXd makeScancontext( pcl::PointCloud & _scan_down ); 64 | Eigen::MatrixXd makeRingkeyFromScancontext( Eigen::MatrixXd &_desc ); 65 | Eigen::MatrixXd makeSectorkeyFromScancontext( Eigen::MatrixXd &_desc ); 66 | 67 | int fastAlignUsingVkey ( MatrixXd & _vkey1, MatrixXd & _vkey2 ); 68 | double distDirectSC ( MatrixXd &_sc1, MatrixXd &_sc2 ); // "d" (eq 5) in the original paper (IROS 18) 69 | std::pair distanceBtnScanContext ( MatrixXd &_sc1, MatrixXd &_sc2 ); // "D" (eq 6) in the original paper (IROS 18) 70 | 71 | // User-side API 72 | void makeAndSaveScancontextAndKeys( pcl::PointCloud & _scan_down ); 73 | std::pair detectLoopClosureID( void ); // int: nearest node index, float: relative yaw 74 | 75 | public: 76 | // hyper parameters () 77 | const double LIDAR_HEIGHT = 2.0; // lidar height : add this for simply directly using lidar scan in the lidar local coord (not robot base coord) / if you use robot-coord-transformed lidar scans, just set this as 0. 78 | 79 | const int PC_NUM_RING = 20; // 20 in the original paper (IROS 18) 80 | const int PC_NUM_SECTOR = 60; // 60 in the original paper (IROS 18) 81 | const double PC_MAX_RADIUS = 80.0; // 80 meter max in the original paper (IROS 18) 82 | const double PC_UNIT_SECTORANGLE = 360.0 / double(PC_NUM_SECTOR); 83 | const double PC_UNIT_RINGGAP = PC_MAX_RADIUS / double(PC_NUM_RING); 84 | 85 | // tree 86 | const int NUM_EXCLUDE_RECENT = 50; // simply just keyframe gap, but node position distance-based exclusion is ok. 87 | const int NUM_CANDIDATES_FROM_TREE = 10; // 10 is enough. (refer the IROS 18 paper) 88 | 89 | // loop thres 90 | const double SEARCH_RATIO = 0.1; // for fast comparison, no Brute-force, but search 10 % is okay. // not was in the original conf paper, but improved ver. 91 | // const double SC_DIST_THRES = 0.13; // empirically 0.1-0.2 is fine (rare false-alarms) for 20x60 polar context (but for 0.15 <, DCS or ICP fit score check (e.g., in LeGO-LOAM) should be required for robustness) 92 | const double SC_DIST_THRES = 0.3; // 0.4-0.6 is good choice for using with robust kernel (e.g., Cauchy, DCS) + icp fitness threshold / if not, recommend 0.1-0.15 93 | 94 | // config 95 | const int TREE_MAKING_PERIOD_ = 10; // i.e., remaking tree frequency, to avoid non-mandatory every remaking, to save time cost / in the LeGO-LOAM integration, it is synchronized with the loop detection callback (which is 1Hz) so it means the tree is updated evrey 10 sec. But you can use the smaller value because it is enough fast ~ 5-50ms wrt N. 96 | int tree_making_period_conter = 0; 97 | 98 | // data 99 | std::vector polarcontexts_timestamp_; // optional. 100 | std::vector polarcontexts_; 101 | std::vector polarcontext_invkeys_; 102 | std::vector polarcontext_vkeys_; 103 | 104 | KeyMat polarcontext_invkeys_mat_; 105 | KeyMat polarcontext_invkeys_to_search_; 106 | std::unique_ptr polarcontext_tree_; 107 | 108 | }; // SCManager 109 | 110 | // } // namespace SC2 111 | -------------------------------------------------------------------------------- /C-LOAM/include/tictoc.h: -------------------------------------------------------------------------------- 1 | // Author: Tong Qin qintonguav@gmail.com 2 | // Shaozu Cao saozu.cao@connect.ust.hk 3 | 4 | #pragma once 5 | 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | class TicToc 13 | { 14 | public: 15 | TicToc() 16 | { 17 | tic(); 18 | } 19 | 20 | TicToc( bool _disp ) 21 | { 22 | disp_ = _disp; 23 | tic(); 24 | } 25 | 26 | void tic() 27 | { 28 | start = std::chrono::system_clock::now(); 29 | } 30 | 31 | void toc( std::string _about_task ) 32 | { 33 | end = std::chrono::system_clock::now(); 34 | std::chrono::duration elapsed_seconds = end - start; 35 | double elapsed_ms = elapsed_seconds.count() * 1000; 36 | 37 | if( disp_ ) 38 | { 39 | std::cout.precision(3); // 10 for sec, 3 for ms 40 | std::cout << _about_task << ": " << elapsed_ms << " msec." << std::endl; 41 | } 42 | } 43 | 44 | private: 45 | std::chrono::time_point start, end; 46 | bool disp_ = false; 47 | }; 48 | -------------------------------------------------------------------------------- /C-LOAM/include/util.h: -------------------------------------------------------------------------------- 1 | #ifndef _UTILITY_LIDAR_ODOMETRY_H_ 2 | #define _UTILITY_LIDAR_ODOMETRY_H_ 3 | 4 | 5 | #include 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | #include "cloud_msgs/cloud_info.h" 12 | 13 | #include 14 | 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | #include 24 | #include 25 | 26 | #include 27 | #include 28 | 29 | #include 30 | #include 31 | #include 32 | #include 33 | #include 34 | #include 35 | #include 36 | #include 37 | #include 38 | #include 39 | #include 40 | #include 41 | #include 42 | #include 43 | #include 44 | #include 45 | #include 46 | 47 | #include 48 | #include 49 | #include 50 | #include 51 | #include 52 | #include 53 | #include 54 | #include 55 | 56 | #define PI 3.14159265 57 | 58 | using namespace std; 59 | // rosbag filter "HK-Data20190316-2 20190331_NJ_LL.bag" "lidaronly_HK-Data20190316-2 20190331_NJ_LL.bag" "topic == '/velodyne_points'" 60 | // rosbag filter "HK-Data20190117.bag" "lidaronly_HK-Data20190117.bag" "topic == '/velodyne_points'" 61 | 62 | typedef pcl::PointXYZI PointType; 63 | 64 | extern const string pointCloudTopic = "/points_raw"; 65 | // extern const string pointCloudTopic = "/kitti/velo/pointcloud"; 66 | // extern const string pointCloudTopic = "/velodyne_points"; 67 | // extern const string pointCloudTopic = "/velodyne_points_0"; 68 | extern const string imuTopic = "/imu_no_use"; 69 | 70 | // Save pcd 71 | extern const string fileDirectory = "/tmp/"; 72 | 73 | // Using velodyne cloud "ring" channel for image projection (other lidar may have different name for this channel, change "PointXYZIR" below) 74 | extern const bool useCloudRing = false; // if true, ang_res_y and ang_bottom are not used 75 | 76 | // VLP-16 77 | // extern const int N_SCAN = 16; 78 | // extern const int Horizon_SCAN = 1800; 79 | // extern const float ang_res_x = 0.2; 80 | // extern const float ang_res_y = 2.0; 81 | // extern const float ang_bottom = 15.0+0.1; 82 | // extern const int groundScanInd = 7; 83 | 84 | // HDL-32E 85 | // extern const int N_SCAN = 32; 86 | // extern const int Horizon_SCAN = 1800; 87 | // extern const float ang_res_x = 360.0/float(Horizon_SCAN); 88 | // extern const float ang_res_y = 41.33/float(N_SCAN-1); 89 | // extern const float ang_bottom = 30.67; 90 | // extern const int groundScanInd = 20; 91 | 92 | // HDL-64E 93 | extern const int N_SCAN = 64; 94 | extern const int Horizon_SCAN = 1800; 95 | extern const float ang_res_x = 360.0/float(Horizon_SCAN); 96 | extern const float ang_res_y = 41.33/float(N_SCAN-1); 97 | extern const float ang_bottom = 30.67; 98 | extern const int groundScanInd = 30; 99 | 100 | // VLS-128 101 | // extern const int N_SCAN = 128; 102 | // extern const int Horizon_SCAN = 1800; 103 | // extern const float ang_res_x = 0.2; 104 | // extern const float ang_res_y = 0.3; 105 | // extern const float ang_bottom = 25.0; 106 | // extern const int groundScanInd = 10; 107 | 108 | // Ouster users may need to uncomment line 159 in imageProjection.cpp 109 | // Usage of Ouster imu data is not fully supported yet (LeGO-LOAM needs 9-DOF IMU), please just publish point cloud data 110 | // Ouster OS1-16 111 | // extern const int N_SCAN = 16; 112 | // extern const int Horizon_SCAN = 1024; 113 | // extern const float ang_res_x = 360.0/float(Horizon_SCAN); 114 | // extern const float ang_res_y = 33.2/float(N_SCAN-1); 115 | // extern const float ang_bottom = 16.6+0.1; 116 | // extern const int groundScanInd = 7; 117 | 118 | // Ouster OS1-64 119 | // extern const int N_SCAN = 64; 120 | // extern const int Horizon_SCAN = 1024; 121 | // extern const float ang_res_x = 360.0/float(Horizon_SCAN); 122 | // extern const float ang_res_y = 33.2/float(N_SCAN-1); 123 | // extern const float ang_bottom = 16.6+0.1; 124 | // extern const int groundScanInd = 15; 125 | 126 | extern const bool loopClosureEnableFlag = true; 127 | extern const double mappingProcessInterval = 0.3; 128 | 129 | extern const float scanPeriod = 0.1; 130 | extern const int systemDelay = 0; 131 | extern const int imuQueLength = 200; 132 | 133 | extern const float sensorMinimumRange = 1.0; 134 | extern const float sensorMountAngle = 0.0; 135 | extern const float segmentTheta = 60.0/180.0*M_PI; // decrese this value may improve accuracy 136 | extern const int segmentValidPointNum = 5; 137 | extern const int segmentValidLineNum = 3; 138 | extern const float segmentAlphaX = ang_res_x / 180.0 * M_PI; 139 | extern const float segmentAlphaY = ang_res_y / 180.0 * M_PI; 140 | 141 | 142 | extern const int edgeFeatureNum = 2; 143 | extern const int surfFeatureNum = 4; 144 | extern const int sectionsTotal = 6; 145 | extern const float edgeThreshold = 0.1; 146 | extern const float surfThreshold = 0.1; 147 | extern const float nearestFeatureSearchSqDist = 25; 148 | 149 | 150 | // Mapping Params 151 | extern const float surroundingKeyframeSearchRadius = 50.0; // key frame that is within n meters from current pose will be considerd for scan-to-map optimization (when loop closure disabled) 152 | extern const int surroundingKeyframeSearchNum = 50; // submap size (when loop closure enabled) 153 | 154 | // history key frames (history submap for loop closure) 155 | extern const float historyKeyframeSearchRadius = 20.0; // NOT used in Scan Context-based loop detector / default 7.0; key frame that is within n meters from current pose will be considerd for loop closure 156 | extern const int historyKeyframeSearchNum = 25; // 2n+1 number of history key frames will be fused into a submap for loop closure 157 | extern const float historyKeyframeFitnessScore = 0.3; // default 0.3; the smaller the better alignment 1.5 158 | 159 | extern const float globalMapVisualizationSearchRadius = 1500.0; // key frames with in n meters will be visualized 160 | 161 | bool use_ransac_ground_segment = 0; 162 | 163 | double MINIMUM_RANGE = 0.1; 164 | double image_res = 3.0; 165 | double V_FOV_UP = 5; 166 | double V_FOV_DOWN = -25; 167 | double H_FOV = 360; //100 168 | double V_FOV = std::abs(V_FOV_UP) + std::abs(V_FOV_DOWN); 169 | 170 | bool use_dynamic_removal = false; 171 | bool use_new_ground_segment = false; 172 | bool use_ground_contraint = false; 173 | bool usingRawCloud = true; 174 | bool usingSubFeature = true; 175 | 176 | struct smoothness_t{ 177 | float value; 178 | size_t ind; 179 | }; 180 | 181 | struct by_value{ 182 | bool operator()(smoothness_t const &left, smoothness_t const &right) { 183 | return left.value < right.value; 184 | } 185 | }; 186 | 187 | /* 188 | * A point cloud type that has "ring" channel 189 | */ 190 | struct PointXYZIR 191 | { 192 | PCL_ADD_POINT4D 193 | PCL_ADD_INTENSITY; 194 | uint16_t ring; 195 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 196 | } EIGEN_ALIGN16; 197 | 198 | POINT_CLOUD_REGISTER_POINT_STRUCT (PointXYZIR, 199 | (float, x, x) (float, y, y) 200 | (float, z, z) (float, intensity, intensity) 201 | (uint16_t, ring, ring) 202 | ) 203 | 204 | /* 205 | * A point cloud type that has 6D pose info ([x,y,z,roll,pitch,yaw] intensity is time stamp) 206 | */ 207 | struct PointXYZIRPYT 208 | { 209 | PCL_ADD_POINT4D 210 | PCL_ADD_INTENSITY; 211 | float roll; 212 | float pitch; 213 | float yaw; 214 | double time; 215 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 216 | } EIGEN_ALIGN16; 217 | 218 | POINT_CLOUD_REGISTER_POINT_STRUCT (PointXYZIRPYT, 219 | (float, x, x) (float, y, y) 220 | (float, z, z) (float, intensity, intensity) 221 | (float, roll, roll) (float, pitch, pitch) (float, yaw, yaw) 222 | (double, time, time) 223 | ) 224 | 225 | typedef PointXYZIRPYT PointTypePose; 226 | 227 | template 228 | constexpr const T& clamp( const T& v, const T& lo, const T& hi ) 229 | { 230 | assert( !(hi < lo) ); 231 | return v < lo ? lo : hi < v ? hi : v; 232 | } 233 | 234 | template 235 | std::vector linspace(T a, T b, size_t N) { 236 | T h = (b - a) / static_cast(N-1); 237 | std::vector xs(N); 238 | typename std::vector::iterator x; 239 | T val; 240 | for (x = xs.begin(), val = a; x != xs.end(); ++x, val += h) 241 | *x = val; 242 | return xs; 243 | } 244 | 245 | #endif 246 | -------------------------------------------------------------------------------- /C-LOAM/launch/run.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /C-LOAM/launch/test.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 171 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: 7 | - /TF1/Frames1 8 | Splitter Ratio: 0.7039999961853027 9 | Tree Height: 270 10 | - Class: rviz/Selection 11 | Name: Selection 12 | - Class: rviz/Tool Properties 13 | Expanded: ~ 14 | Name: Tool Properties 15 | Splitter Ratio: 0.5886790156364441 16 | - Class: rviz/Views 17 | Expanded: 18 | - /Current View1 19 | Name: Views 20 | Splitter Ratio: 0.5 21 | - Class: rviz/Time 22 | Name: Time 23 | SyncMode: 0 24 | SyncSource: Edge Features (green) 25 | - Class: rviz/Help 26 | Name: Help 27 | Preferences: 28 | PromptSaveOnExit: true 29 | Toolbars: 30 | toolButtonStyle: 2 31 | Visualization Manager: 32 | Class: "" 33 | Displays: 34 | - Class: rviz/TF 35 | Enabled: false 36 | Filter (blacklist): "" 37 | Filter (whitelist): "" 38 | Frame Timeout: 15 39 | Frames: 40 | All Enabled: false 41 | Marker Alpha: 1 42 | Marker Scale: 10 43 | Name: TF 44 | Show Arrows: true 45 | Show Axes: true 46 | Show Names: true 47 | Tree: 48 | {} 49 | Update Interval: 0 50 | Value: false 51 | - Alpha: 1 52 | Class: rviz/Axes 53 | Enabled: true 54 | Length: 2 55 | Name: map 56 | Radius: 0.30000001192092896 57 | Reference Frame: map 58 | Show Trail: false 59 | Value: true 60 | - Alpha: 1 61 | Class: rviz/Axes 62 | Enabled: true 63 | Length: 1 64 | Name: base_link 65 | Radius: 0.5 66 | Reference Frame: base_link 67 | Show Trail: false 68 | Value: true 69 | - Alpha: 1 70 | Autocompute Intensity Bounds: true 71 | Autocompute Value Bounds: 72 | Max Value: 17.005943298339844 73 | Min Value: -1.0478858947753906 74 | Value: true 75 | Axis: Z 76 | Channel Name: intensity 77 | Class: rviz/PointCloud2 78 | Color: 255; 0; 0 79 | Color Transformer: AxisColor 80 | Decay Time: 0 81 | Enabled: false 82 | Invert Rainbow: false 83 | Max Color: 255; 255; 255 84 | Min Color: 0; 0; 0 85 | Name: Velodyne 86 | Position Transformer: XYZ 87 | Queue Size: 2 88 | Selectable: true 89 | Size (Pixels): 3 90 | Size (m): 0.009999999776482582 91 | Style: Points 92 | Topic: /full_cloud_projected 93 | Unreliable: false 94 | Use Fixed Frame: true 95 | Use rainbow: true 96 | Value: false 97 | - Alpha: 1 98 | Autocompute Intensity Bounds: true 99 | Autocompute Value Bounds: 100 | Max Value: 20.456600189208984 101 | Min Value: -3.5830700397491455 102 | Value: true 103 | Axis: Z 104 | Channel Name: intensity 105 | Class: rviz/PointCloud2 106 | Color: 255; 255; 0 107 | Color Transformer: FlatColor 108 | Decay Time: 0 109 | Enabled: false 110 | Invert Rainbow: false 111 | Max Color: 255; 255; 255 112 | Min Color: 0; 0; 0 113 | Name: Surface (yellow) 114 | Position Transformer: XYZ 115 | Queue Size: 2 116 | Selectable: true 117 | Size (Pixels): 8 118 | Size (m): 0.009999999776482582 119 | Style: Points 120 | Topic: /laser_cloud_flat 121 | Unreliable: false 122 | Use Fixed Frame: true 123 | Use rainbow: true 124 | Value: false 125 | - Alpha: 1 126 | Autocompute Intensity Bounds: true 127 | Autocompute Value Bounds: 128 | Max Value: 20.456600189208984 129 | Min Value: -3.5830700397491455 130 | Value: true 131 | Axis: Z 132 | Channel Name: intensity 133 | Class: rviz/PointCloud2 134 | Color: 110; 132; 255 135 | Color Transformer: FlatColor 136 | Decay Time: 0 137 | Enabled: false 138 | Invert Rainbow: false 139 | Max Color: 255; 255; 255 140 | Min Color: 0; 0; 0 141 | Name: Edge Sharp (blue) 142 | Position Transformer: XYZ 143 | Queue Size: 2 144 | Selectable: true 145 | Size (Pixels): 8 146 | Size (m): 0.009999999776482582 147 | Style: Points 148 | Topic: /laser_cloud_sharp 149 | Unreliable: false 150 | Use Fixed Frame: true 151 | Use rainbow: true 152 | Value: false 153 | - Alpha: 1 154 | Autocompute Intensity Bounds: true 155 | Autocompute Value Bounds: 156 | Max Value: 20.456600189208984 157 | Min Value: -3.5830700397491455 158 | Value: true 159 | Axis: Z 160 | Channel Name: intensity 161 | Class: rviz/PointCloud2 162 | Color: 0; 255; 0 163 | Color Transformer: FlatColor 164 | Decay Time: 0 165 | Enabled: true 166 | Invert Rainbow: false 167 | Max Color: 255; 255; 255 168 | Min Color: 0; 0; 0 169 | Name: Edge Features (green) 170 | Position Transformer: XYZ 171 | Queue Size: 2 172 | Selectable: true 173 | Size (Pixels): 5 174 | Size (m): 0.009999999776482582 175 | Style: Points 176 | Topic: /laser_cloud_less_sharp 177 | Unreliable: false 178 | Use Fixed Frame: true 179 | Use rainbow: true 180 | Value: true 181 | - Alpha: 1 182 | Autocompute Intensity Bounds: true 183 | Autocompute Value Bounds: 184 | Max Value: 20.456600189208984 185 | Min Value: -3.5830700397491455 186 | Value: true 187 | Axis: Z 188 | Channel Name: intensity 189 | Class: rviz/PointCloud2 190 | Color: 255; 170; 255 191 | Color Transformer: FlatColor 192 | Decay Time: 0 193 | Enabled: true 194 | Invert Rainbow: false 195 | Max Color: 255; 255; 255 196 | Min Color: 0; 0; 0 197 | Name: Surface Features (pink) 198 | Position Transformer: XYZ 199 | Queue Size: 2 200 | Selectable: true 201 | Size (Pixels): 3 202 | Size (m): 0.009999999776482582 203 | Style: Points 204 | Topic: /laser_cloud_less_flat 205 | Unreliable: false 206 | Use Fixed Frame: true 207 | Use rainbow: true 208 | Value: true 209 | - Alpha: 1 210 | Autocompute Intensity Bounds: true 211 | Autocompute Value Bounds: 212 | Max Value: 10.7253999710083 213 | Min Value: -6.348199844360352 214 | Value: true 215 | Axis: Z 216 | Channel Name: intensity 217 | Class: rviz/PointCloud2 218 | Color: 255; 255; 255 219 | Color Transformer: FlatColor 220 | Decay Time: 0 221 | Enabled: false 222 | Invert Rainbow: false 223 | Max Color: 255; 255; 255 224 | Min Color: 0; 0; 0 225 | Name: Outlier Cloud 226 | Position Transformer: XYZ 227 | Queue Size: 2 228 | Selectable: true 229 | Size (Pixels): 3 230 | Size (m): 0.009999999776482582 231 | Style: Points 232 | Topic: /outlier_cloud 233 | Unreliable: false 234 | Use Fixed Frame: true 235 | Use rainbow: true 236 | Value: false 237 | - Alpha: 1 238 | Autocompute Intensity Bounds: true 239 | Autocompute Value Bounds: 240 | Max Value: 10 241 | Min Value: -10 242 | Value: true 243 | Axis: Z 244 | Channel Name: intensity 245 | Class: rviz/PointCloud2 246 | Color: 0; 0; 255 247 | Color Transformer: Intensity 248 | Decay Time: 0 249 | Enabled: false 250 | Invert Rainbow: false 251 | Max Color: 255; 255; 255 252 | Min Color: 0; 0; 0 253 | Name: Segmentation Full 254 | Position Transformer: XYZ 255 | Queue Size: 10 256 | Selectable: true 257 | Size (Pixels): 3 258 | Size (m): 0.009999999776482582 259 | Style: Points 260 | Topic: /segmented_cloud 261 | Unreliable: false 262 | Use Fixed Frame: true 263 | Use rainbow: true 264 | Value: false 265 | - Alpha: 1 266 | Autocompute Intensity Bounds: true 267 | Autocompute Value Bounds: 268 | Max Value: 10 269 | Min Value: -10 270 | Value: true 271 | Axis: Z 272 | Channel Name: intensity 273 | Class: rviz/PointCloud2 274 | Color: 255; 255; 255 275 | Color Transformer: Intensity 276 | Decay Time: 0 277 | Enabled: false 278 | Invert Rainbow: false 279 | Max Color: 255; 255; 255 280 | Min Color: 0; 0; 0 281 | Name: Segmentation Pure 282 | Position Transformer: XYZ 283 | Queue Size: 10 284 | Selectable: true 285 | Size (Pixels): 5 286 | Size (m): 0.009999999776482582 287 | Style: Points 288 | Topic: /segmented_cloud_pure 289 | Unreliable: false 290 | Use Fixed Frame: true 291 | Use rainbow: true 292 | Value: false 293 | - Alpha: 1 294 | Autocompute Intensity Bounds: true 295 | Autocompute Value Bounds: 296 | Max Value: 18.959199905395508 297 | Min Value: 0.04049830138683319 298 | Value: true 299 | Axis: Z 300 | Channel Name: intensity 301 | Class: rviz/PointCloud2 302 | Color: 255; 0; 127 303 | Color Transformer: FlatColor 304 | Decay Time: 0 305 | Enabled: false 306 | Invert Rainbow: false 307 | Max Color: 255; 255; 255 308 | Min Color: 0; 0; 0 309 | Name: Ground Cloud 310 | Position Transformer: XYZ 311 | Queue Size: 10 312 | Selectable: true 313 | Size (Pixels): 3 314 | Size (m): 0.009999999776482582 315 | Style: Points 316 | Topic: /ground_cloud 317 | Unreliable: false 318 | Use Fixed Frame: true 319 | Use rainbow: true 320 | Value: false 321 | - Alpha: 1 322 | Autocompute Intensity Bounds: true 323 | Autocompute Value Bounds: 324 | Max Value: 4.570899963378906 325 | Min Value: 0.30000001192092896 326 | Value: true 327 | Axis: Z 328 | Channel Name: intensity 329 | Class: rviz/PointCloud2 330 | Color: 239; 41; 41 331 | Color Transformer: FlatColor 332 | Decay Time: 0 333 | Enabled: true 334 | Invert Rainbow: false 335 | Max Color: 255; 255; 255 336 | Min Color: 0; 0; 0 337 | Name: Keframes 338 | Position Transformer: XYZ 339 | Queue Size: 1 340 | Selectable: true 341 | Size (Pixels): 3 342 | Size (m): 1 343 | Style: Boxes 344 | Topic: /key_pose_origin 345 | Unreliable: false 346 | Use Fixed Frame: true 347 | Use rainbow: true 348 | Value: true 349 | - Alpha: 1 350 | Autocompute Intensity Bounds: true 351 | Autocompute Value Bounds: 352 | Max Value: 10 353 | Min Value: -10 354 | Value: true 355 | Axis: Z 356 | Channel Name: intensity 357 | Class: rviz/PointCloud2 358 | Color: 255; 255; 255 359 | Color Transformer: Intensity 360 | Decay Time: 0 361 | Enabled: false 362 | Invert Rainbow: false 363 | Max Color: 255; 255; 255 364 | Min Color: 0; 0; 0 365 | Name: ICP cloud 366 | Position Transformer: XYZ 367 | Queue Size: 10 368 | Selectable: true 369 | Size (Pixels): 5 370 | Size (m): 0.009999999776482582 371 | Style: Points 372 | Topic: /corrected_cloud 373 | Unreliable: false 374 | Use Fixed Frame: true 375 | Use rainbow: true 376 | Value: false 377 | - Alpha: 1 378 | Autocompute Intensity Bounds: true 379 | Autocompute Value Bounds: 380 | Max Value: 10 381 | Min Value: -10 382 | Value: true 383 | Axis: Z 384 | Channel Name: intensity 385 | Class: rviz/PointCloud2 386 | Color: 255; 255; 255 387 | Color Transformer: FlatColor 388 | Decay Time: 0 389 | Enabled: false 390 | Invert Rainbow: false 391 | Max Color: 255; 255; 255 392 | Min Color: 0; 0; 0 393 | Name: History Key Frames 394 | Position Transformer: XYZ 395 | Queue Size: 10 396 | Selectable: true 397 | Size (Pixels): 2 398 | Size (m): 0.009999999776482582 399 | Style: Points 400 | Topic: /history_cloud 401 | Unreliable: false 402 | Use Fixed Frame: true 403 | Use rainbow: true 404 | Value: false 405 | - Alpha: 1 406 | Autocompute Intensity Bounds: true 407 | Autocompute Value Bounds: 408 | Max Value: 218.9891357421875 409 | Min Value: -71.57814025878906 410 | Value: true 411 | Axis: Z 412 | Channel Name: intensity 413 | Class: rviz/PointCloud2 414 | Color: 136; 138; 133 415 | Color Transformer: AxisColor 416 | Decay Time: 0 417 | Enabled: true 418 | Invert Rainbow: false 419 | Max Color: 255; 255; 255 420 | Min Color: 0; 0; 0 421 | Name: Map Cloud 422 | Position Transformer: XYZ 423 | Queue Size: 10 424 | Selectable: true 425 | Size (Pixels): 1 426 | Size (m): 0.009999999776482582 427 | Style: Points 428 | Topic: /laser_cloud_surround 429 | Unreliable: false 430 | Use Fixed Frame: false 431 | Use rainbow: false 432 | Value: true 433 | - Alpha: 0.5 434 | Autocompute Intensity Bounds: true 435 | Autocompute Value Bounds: 436 | Max Value: 52.99140548706055 437 | Min Value: 20.528194427490234 438 | Value: true 439 | Axis: Y 440 | Channel Name: intensity 441 | Class: rviz/PointCloud2 442 | Color: 255; 255; 255 443 | Color Transformer: AxisColor 444 | Decay Time: 300 445 | Enabled: false 446 | Invert Rainbow: false 447 | Max Color: 255; 255; 255 448 | Min Color: 0; 0; 0 449 | Name: Map Cloud (stack) 450 | Position Transformer: XYZ 451 | Queue Size: 10 452 | Selectable: true 453 | Size (Pixels): 2 454 | Size (m): 0.009999999776482582 455 | Style: Points 456 | Topic: /registered_cloud 457 | Unreliable: false 458 | Use Fixed Frame: false 459 | Use rainbow: false 460 | Value: false 461 | - Alpha: 1 462 | Autocompute Intensity Bounds: true 463 | Autocompute Value Bounds: 464 | Max Value: 20.21147346496582 465 | Min Value: -2.7048606872558594 466 | Value: true 467 | Axis: Z 468 | Channel Name: intensity 469 | Class: rviz/PointCloud2 470 | Color: 170; 255; 255 471 | Color Transformer: AxisColor 472 | Decay Time: 0 473 | Enabled: false 474 | Invert Rainbow: false 475 | Max Color: 255; 255; 255 476 | Min Color: 0; 0; 0 477 | Name: Surround Cloud 478 | Position Transformer: XYZ 479 | Queue Size: 10 480 | Selectable: true 481 | Size (Pixels): 2 482 | Size (m): 0.009999999776482582 483 | Style: Points 484 | Topic: /recent_cloud 485 | Unreliable: false 486 | Use Fixed Frame: true 487 | Use rainbow: true 488 | Value: false 489 | - Class: rviz/Image 490 | Enabled: true 491 | Image Topic: /range_image_last 492 | Max Value: 1 493 | Median window: 5 494 | Min Value: 0 495 | Name: Range Image Now 496 | Normalize Range: true 497 | Queue Size: 2 498 | Transport Hint: raw 499 | Unreliable: false 500 | Value: true 501 | - Class: rviz/Image 502 | Enabled: true 503 | Image Topic: /range_image_now 504 | Max Value: 1 505 | Median window: 5 506 | Min Value: 0 507 | Name: Range Image Last 508 | Normalize Range: true 509 | Queue Size: 2 510 | Transport Hint: raw 511 | Unreliable: false 512 | Value: true 513 | - Class: rviz/MarkerArray 514 | Enabled: true 515 | Marker Topic: /loop_closure_constraints 516 | Name: Loop Closure 517 | Namespaces: 518 | loop_edges: true 519 | loop_nodes: true 520 | Queue Size: 100 521 | Value: true 522 | - Alpha: 1 523 | Buffer Length: 1 524 | Class: rviz/Path 525 | Color: 255; 255; 255 526 | Enabled: true 527 | Head Diameter: 0.30000001192092896 528 | Head Length: 0.20000000298023224 529 | Length: 10 530 | Line Style: Billboards 531 | Line Width: 0.30000001192092896 532 | Name: Trajectory 533 | Offset: 534 | X: 0 535 | Y: 0 536 | Z: 0 537 | Pose Color: 255; 85; 255 538 | Pose Style: None 539 | Queue Size: 10 540 | Radius: 0.029999999329447746 541 | Shaft Diameter: 0.10000000149011612 542 | Shaft Length: 0.10000000149011612 543 | Topic: /global_pose_graph_path 544 | Unreliable: false 545 | Value: true 546 | Enabled: true 547 | Global Options: 548 | Background Color: 0; 0; 0 549 | Default Light: true 550 | Fixed Frame: camera_init 551 | Frame Rate: 30 552 | Name: root 553 | Tools: 554 | - Class: rviz/Interact 555 | Hide Inactive Objects: true 556 | - Class: rviz/FocusCamera 557 | - Class: rviz/Measure 558 | Value: true 559 | Views: 560 | Current: 561 | Class: rviz/FrameAligned 562 | Enable Stereo Rendering: 563 | Stereo Eye Separation: 0.05999999865889549 564 | Stereo Focal Distance: 1 565 | Swap Stereo Eyes: false 566 | Value: false 567 | Invert Z Axis: false 568 | Lock Camera: false 569 | Name: Current View 570 | Near Clip Distance: 0.009999999776482582 571 | Pitch: -2.3267791271209717 572 | Point towards: arbitrary 573 | Position: 574 | X: -4.368364334106445 575 | Y: 74.38995361328125 576 | Z: -58.711997985839844 577 | Roll: 3.1415927410125732 578 | Target Frame: aft_mapped 579 | Yaw: 1.5581456422805786 580 | Saved: ~ 581 | Window Geometry: 582 | Displays: 583 | collapsed: true 584 | Height: 1016 585 | Help: 586 | collapsed: false 587 | Hide Left Dock: true 588 | Hide Right Dock: true 589 | QMainWindow State: 000000ff00000000fd00000004000000000000017900000323fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007300000000b800000323000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000800480065006c0070000000032c000000ba0000006e00ffffff000000010000010f00000323fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000b800000323000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b20000000000000000000000020000074b00000075fc0100000005fb0000001e00520061006e0067006500200049006d0061006700650020004e006f00770100000000000003a2000000c700fffffffb0000002000520061006e0067006500200049006d0061006700650020004c00610073007401000003a8000003a3000000c400fffffffb0000001600520061006e0067006500200049006d00610067006500000000000000073f0000000000000000fb0000000a0049006d0061006700650000000000000006100000000000000000fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073e0000003efc0100000002fb0000000800540069006d006500000000000000073e0000041800fffffffb0000000800540069006d006501000000000000045000000000000000000000074b0000032300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 590 | Range Image Last: 591 | collapsed: false 592 | Range Image Now: 593 | collapsed: false 594 | Selection: 595 | collapsed: false 596 | Time: 597 | collapsed: false 598 | Tool Properties: 599 | collapsed: false 600 | Views: 601 | collapsed: true 602 | Width: 1867 603 | X: 693 604 | Y: 27 605 | -------------------------------------------------------------------------------- /C-LOAM/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | c_loam 4 | 1.0.0 5 | C-LOAM from ICUS 2024 6 | 7 | Yanpeng Jia 8 | 9 | BSD 10 | 11 | Yanpeng Jia 12 | 13 | catkin 14 | 15 | roscpp 16 | roscpp 17 | rospy 18 | rospy 19 | ros_bridge 20 | ros_bridge 21 | 22 | tf 23 | tf 24 | 25 | pcl_ros 26 | pcl_ros 27 | pcl_conversions 28 | pcl_conversions 29 | 30 | cv_bridge 31 | cv_bridge 32 | 33 | std_msgs 34 | std_msgs 35 | cloud_msgs 36 | cloud_msgs 37 | sensors_msgs 38 | sensors_msgs 39 | geometry_msgs 40 | geometry_msgs 41 | nav_msgs 42 | nav_msgs 43 | 44 | image_transport 45 | image_transport 46 | 47 | gtsam 48 | gtsam 49 | 50 | cv_bridge 51 | cv_bridge 52 | image_transport 53 | image_transport 54 | 55 | 56 | -------------------------------------------------------------------------------- /C-LOAM/src/Scancontext.cpp: -------------------------------------------------------------------------------- 1 | #include "Scancontext.h" 2 | 3 | // namespace SC2 4 | // { 5 | 6 | void coreImportTest (void) 7 | { 8 | cout << "scancontext lib is successfully imported." << endl; 9 | } // coreImportTest 10 | 11 | 12 | float rad2deg(float radians) 13 | { 14 | return radians * 180.0 / M_PI; 15 | } 16 | 17 | float deg2rad(float degrees) 18 | { 19 | return degrees * M_PI / 180.0; 20 | } 21 | 22 | 23 | float xy2theta( const float & _x, const float & _y ) 24 | { 25 | if ( _x >= 0 & _y >= 0) 26 | return (180/M_PI) * atan(_y / _x); 27 | 28 | if ( _x < 0 & _y >= 0) 29 | return 180 - ( (180/M_PI) * atan(_y / (-_x)) ); 30 | 31 | if ( _x < 0 & _y < 0) 32 | return 180 + ( (180/M_PI) * atan(_y / _x) ); 33 | 34 | if ( _x >= 0 & _y < 0) 35 | return 360 - ( (180/M_PI) * atan((-_y) / _x) ); 36 | } // xy2theta 37 | 38 | 39 | MatrixXd circshift( MatrixXd &_mat, int _num_shift ) 40 | { 41 | // shift columns to right direction 42 | assert(_num_shift >= 0); 43 | 44 | if( _num_shift == 0 ) 45 | { 46 | MatrixXd shifted_mat( _mat ); 47 | return shifted_mat; // Early return 48 | } 49 | 50 | MatrixXd shifted_mat = MatrixXd::Zero( _mat.rows(), _mat.cols() ); 51 | for ( int col_idx = 0; col_idx < _mat.cols(); col_idx++ ) 52 | { 53 | int new_location = (col_idx + _num_shift) % _mat.cols(); 54 | shifted_mat.col(new_location) = _mat.col(col_idx); 55 | } 56 | 57 | return shifted_mat; 58 | 59 | } // circshift 60 | 61 | 62 | std::vector eig2stdvec( MatrixXd _eigmat ) 63 | { 64 | std::vector vec( _eigmat.data(), _eigmat.data() + _eigmat.size() ); 65 | return vec; 66 | } // eig2stdvec 67 | 68 | 69 | double SCManager::distDirectSC ( MatrixXd &_sc1, MatrixXd &_sc2 ) 70 | { 71 | int num_eff_cols = 0; // i.e., to exclude all-nonzero sector 72 | double sum_sector_similarity = 0; 73 | for ( int col_idx = 0; col_idx < _sc1.cols(); col_idx++ ) 74 | { 75 | VectorXd col_sc1 = _sc1.col(col_idx); 76 | VectorXd col_sc2 = _sc2.col(col_idx); 77 | 78 | if( col_sc1.norm() == 0 | col_sc2.norm() == 0 ) 79 | continue; // don't count this sector pair. 80 | 81 | double sector_similarity = col_sc1.dot(col_sc2) / (col_sc1.norm() * col_sc2.norm()); 82 | 83 | sum_sector_similarity = sum_sector_similarity + sector_similarity; 84 | num_eff_cols = num_eff_cols + 1; 85 | } 86 | 87 | double sc_sim = sum_sector_similarity / num_eff_cols; 88 | return 1.0 - sc_sim; 89 | 90 | } // distDirectSC 91 | 92 | 93 | int SCManager::fastAlignUsingVkey( MatrixXd & _vkey1, MatrixXd & _vkey2) 94 | { 95 | int argmin_vkey_shift = 0; 96 | double min_veky_diff_norm = 10000000; 97 | for ( int shift_idx = 0; shift_idx < _vkey1.cols(); shift_idx++ ) 98 | { 99 | MatrixXd vkey2_shifted = circshift(_vkey2, shift_idx); 100 | 101 | MatrixXd vkey_diff = _vkey1 - vkey2_shifted; 102 | 103 | double cur_diff_norm = vkey_diff.norm(); 104 | if( cur_diff_norm < min_veky_diff_norm ) 105 | { 106 | argmin_vkey_shift = shift_idx; 107 | min_veky_diff_norm = cur_diff_norm; 108 | } 109 | } 110 | 111 | return argmin_vkey_shift; 112 | 113 | } // fastAlignUsingVkey 114 | 115 | 116 | std::pair SCManager::distanceBtnScanContext( MatrixXd &_sc1, MatrixXd &_sc2 ) 117 | { 118 | // 1. fast align using variant key (not in original IROS18) 119 | MatrixXd vkey_sc1 = makeSectorkeyFromScancontext( _sc1 ); 120 | MatrixXd vkey_sc2 = makeSectorkeyFromScancontext( _sc2 ); 121 | int argmin_vkey_shift = fastAlignUsingVkey( vkey_sc1, vkey_sc2 ); 122 | 123 | const int SEARCH_RADIUS = round( 0.5 * SEARCH_RATIO * _sc1.cols() ); // a half of search range 124 | std::vector shift_idx_search_space { argmin_vkey_shift }; 125 | for ( int ii = 1; ii < SEARCH_RADIUS + 1; ii++ ) 126 | { 127 | shift_idx_search_space.push_back( (argmin_vkey_shift + ii + _sc1.cols()) % _sc1.cols() ); 128 | shift_idx_search_space.push_back( (argmin_vkey_shift - ii + _sc1.cols()) % _sc1.cols() ); 129 | } 130 | std::sort(shift_idx_search_space.begin(), shift_idx_search_space.end()); 131 | 132 | // 2. fast columnwise diff 133 | int argmin_shift = 0; 134 | double min_sc_dist = 10000000; 135 | for ( int num_shift: shift_idx_search_space ) 136 | { 137 | MatrixXd sc2_shifted = circshift(_sc2, num_shift); 138 | double cur_sc_dist = distDirectSC( _sc1, sc2_shifted ); 139 | if( cur_sc_dist < min_sc_dist ) 140 | { 141 | argmin_shift = num_shift; 142 | min_sc_dist = cur_sc_dist; 143 | } 144 | } 145 | 146 | return make_pair(min_sc_dist, argmin_shift); 147 | 148 | } // distanceBtnScanContext 149 | 150 | 151 | MatrixXd SCManager::makeScancontext( pcl::PointCloud & _scan_down ) 152 | { 153 | TicToc t_making_desc; 154 | 155 | int num_pts_scan_down = _scan_down.points.size(); 156 | 157 | // main 158 | const int NO_POINT = -1000; 159 | MatrixXd desc = NO_POINT * MatrixXd::Ones(PC_NUM_RING, PC_NUM_SECTOR); 160 | 161 | SCPointType pt; 162 | float azim_angle, azim_range; // wihtin 2d plane 163 | int ring_idx, sctor_idx; 164 | for (int pt_idx = 0; pt_idx < num_pts_scan_down; pt_idx++) 165 | { 166 | pt.x = _scan_down.points[pt_idx].x; 167 | pt.y = _scan_down.points[pt_idx].y; 168 | pt.z = _scan_down.points[pt_idx].z + LIDAR_HEIGHT; // naive adding is ok (all points should be > 0). 169 | 170 | // xyz to ring, sector 171 | azim_range = sqrt(pt.x * pt.x + pt.y * pt.y); 172 | azim_angle = xy2theta(pt.x, pt.y); 173 | 174 | // if range is out of roi, pass 175 | if( azim_range > PC_MAX_RADIUS ) 176 | continue; 177 | 178 | ring_idx = std::max( std::min( PC_NUM_RING, int(ceil( (azim_range / PC_MAX_RADIUS) * PC_NUM_RING )) ), 1 ); 179 | sctor_idx = std::max( std::min( PC_NUM_SECTOR, int(ceil( (azim_angle / 360.0) * PC_NUM_SECTOR )) ), 1 ); 180 | 181 | // taking maximum z 182 | if ( desc(ring_idx-1, sctor_idx-1) < pt.z ) // -1 means cpp starts from 0 183 | desc(ring_idx-1, sctor_idx-1) = pt.z; // update for taking maximum value at that bin 184 | } 185 | 186 | // reset no points to zero (for cosine dist later) 187 | for ( int row_idx = 0; row_idx < desc.rows(); row_idx++ ) 188 | for ( int col_idx = 0; col_idx < desc.cols(); col_idx++ ) 189 | if( desc(row_idx, col_idx) == NO_POINT ) 190 | desc(row_idx, col_idx) = 0; 191 | 192 | t_making_desc.toc("PolarContext making"); 193 | 194 | return desc; 195 | } // SCManager::makeScancontext 196 | 197 | 198 | MatrixXd SCManager::makeRingkeyFromScancontext( Eigen::MatrixXd &_desc ) 199 | { 200 | /* 201 | * summary: rowwise mean vector 202 | */ 203 | Eigen::MatrixXd invariant_key(_desc.rows(), 1); 204 | for ( int row_idx = 0; row_idx < _desc.rows(); row_idx++ ) 205 | { 206 | Eigen::MatrixXd curr_row = _desc.row(row_idx); 207 | invariant_key(row_idx, 0) = curr_row.mean(); 208 | } 209 | 210 | return invariant_key; 211 | } // SCManager::makeRingkeyFromScancontext 212 | 213 | 214 | MatrixXd SCManager::makeSectorkeyFromScancontext( Eigen::MatrixXd &_desc ) 215 | { 216 | /* 217 | * summary: columnwise mean vector 218 | */ 219 | Eigen::MatrixXd variant_key(1, _desc.cols()); 220 | for ( int col_idx = 0; col_idx < _desc.cols(); col_idx++ ) 221 | { 222 | Eigen::MatrixXd curr_col = _desc.col(col_idx); 223 | variant_key(0, col_idx) = curr_col.mean(); 224 | } 225 | 226 | return variant_key; 227 | } // SCManager::makeSectorkeyFromScancontext 228 | 229 | 230 | void SCManager::makeAndSaveScancontextAndKeys( pcl::PointCloud & _scan_down ) 231 | { 232 | Eigen::MatrixXd sc = makeScancontext(_scan_down); // v1 233 | Eigen::MatrixXd ringkey = makeRingkeyFromScancontext( sc ); 234 | Eigen::MatrixXd sectorkey = makeSectorkeyFromScancontext( sc ); 235 | std::vector polarcontext_invkey_vec = eig2stdvec( ringkey ); 236 | 237 | polarcontexts_.push_back( sc ); 238 | polarcontext_invkeys_.push_back( ringkey ); 239 | polarcontext_vkeys_.push_back( sectorkey ); 240 | polarcontext_invkeys_mat_.push_back( polarcontext_invkey_vec ); 241 | 242 | // cout < SCManager::detectLoopClosureID ( void ) 248 | { 249 | int loop_id { -1 }; // init with -1, -1 means no loop (== LeGO-LOAM's variable "closestHistoryFrameID") 250 | 251 | auto curr_key = polarcontext_invkeys_mat_.back(); // current observation (query) 252 | auto curr_desc = polarcontexts_.back(); // current observation (query) 253 | 254 | /* 255 | * step 1: candidates from ringkey tree_ 256 | */ 257 | if( polarcontext_invkeys_mat_.size() < NUM_EXCLUDE_RECENT + 1) 258 | { 259 | std::pair result {loop_id, 0.0}; 260 | return result; // Early return 261 | } 262 | 263 | // tree_ reconstruction (not mandatory to make everytime) 264 | if( tree_making_period_conter % TREE_MAKING_PERIOD_ == 0) // to save computation cost 265 | { 266 | TicToc t_tree_construction; 267 | 268 | polarcontext_invkeys_to_search_.clear(); 269 | polarcontext_invkeys_to_search_.assign( polarcontext_invkeys_mat_.begin(), polarcontext_invkeys_mat_.end() - NUM_EXCLUDE_RECENT ) ; 270 | 271 | polarcontext_tree_.reset(); 272 | polarcontext_tree_ = std::make_unique(PC_NUM_RING /* dim */, polarcontext_invkeys_to_search_, 10 /* max leaf */ ); 273 | // tree_ptr_->index->buildIndex(); // inernally called in the constructor of InvKeyTree (for detail, refer the nanoflann and KDtreeVectorOfVectorsAdaptor) 274 | t_tree_construction.toc("Tree construction"); 275 | } 276 | tree_making_period_conter = tree_making_period_conter + 1; 277 | 278 | double min_dist = 10000000; // init with somthing large 279 | int nn_align = 0; 280 | int nn_idx = 0; 281 | 282 | // knn search 283 | std::vector candidate_indexes( NUM_CANDIDATES_FROM_TREE ); 284 | std::vector out_dists_sqr( NUM_CANDIDATES_FROM_TREE ); 285 | 286 | TicToc t_tree_search; 287 | nanoflann::KNNResultSet knnsearch_result( NUM_CANDIDATES_FROM_TREE ); 288 | knnsearch_result.init( &candidate_indexes[0], &out_dists_sqr[0] ); 289 | polarcontext_tree_->index->findNeighbors( knnsearch_result, &curr_key[0] /* query */, nanoflann::SearchParams(10) ); 290 | t_tree_search.toc("Tree search"); 291 | 292 | /* 293 | * step 2: pairwise distance (find optimal columnwise best-fit using cosine distance) 294 | */ 295 | TicToc t_calc_dist; 296 | for ( int candidate_iter_idx = 0; candidate_iter_idx < NUM_CANDIDATES_FROM_TREE; candidate_iter_idx++ ) 297 | { 298 | MatrixXd polarcontext_candidate = polarcontexts_[ candidate_indexes[candidate_iter_idx] ]; 299 | std::pair sc_dist_result = distanceBtnScanContext( curr_desc, polarcontext_candidate ); 300 | 301 | double candidate_dist = sc_dist_result.first; 302 | int candidate_align = sc_dist_result.second; 303 | 304 | if( candidate_dist < min_dist ) 305 | { 306 | min_dist = candidate_dist; 307 | nn_align = candidate_align; 308 | 309 | nn_idx = candidate_indexes[candidate_iter_idx]; 310 | } 311 | } 312 | t_calc_dist.toc("Distance calc"); 313 | 314 | /* 315 | * loop threshold check 316 | */ 317 | if( min_dist < SC_DIST_THRES ) 318 | { 319 | loop_id = nn_idx; 320 | 321 | // std::cout.precision(3); 322 | cout << "[Loop found] Nearest distance: " << min_dist << " btn " << polarcontexts_.size()-1 << " and " << nn_idx << "." << endl; 323 | cout << "[Loop found] yaw diff: " << nn_align * PC_UNIT_SECTORANGLE << " deg." << endl; 324 | } 325 | else 326 | { 327 | std::cout.precision(3); 328 | cout << "[Not loop] Nearest distance: " << min_dist << " btn " << polarcontexts_.size()-1 << " and " << nn_idx << "." << endl; 329 | cout << "[Not loop] yaw diff: " << nn_align * PC_UNIT_SECTORANGLE << " deg." << endl; 330 | } 331 | 332 | // To do: return also nn_align (i.e., yaw diff) 333 | float yaw_diff_rad = deg2rad(nn_align * PC_UNIT_SECTORANGLE); 334 | std::pair result {loop_id, yaw_diff_rad}; 335 | 336 | return result; 337 | 338 | } // SCManager::detectLoopClosureID 339 | 340 | // } // namespace SC2 -------------------------------------------------------------------------------- /C-LOAM/src/ceresFactor.hpp: -------------------------------------------------------------------------------- 1 | /**************************************************************************************** 2 | * 3 | * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences 4 | * 5 | * Authors: Yanpeng Jia 6 | * Contact: jiayanpeng@sia.cn 7 | * 8 | ****************************************************************************************/ 9 | #pragma once 10 | 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | 17 | 18 | 19 | template inline 20 | void Quaternion2EulerAngle(const T q[4], T ypr[3]) 21 | { 22 | // roll (x-axis rotation) 23 | T sinr_cosp = T(2) * (q[0] * q[1] + q[2] * q[3]); 24 | T cosr_cosp = T(1) - T(2) * (q[1] * q[1] + q[2] * q[2]); 25 | ypr[2] = atan2(sinr_cosp, cosr_cosp); 26 | 27 | // pitch (y-axis rotation) 28 | T sinp = T(2) * (q[0] * q[2] - q[1] * q[3]); 29 | if (sinp >= T(1)) 30 | { 31 | ypr[1] = T(M_PI / 2); // use 90 degrees if out of range 32 | } 33 | else if (sinp <= T(-1)) 34 | { 35 | ypr[1] = -T(M_PI / 2); // use 90 degrees if out of range 36 | } 37 | else 38 | { 39 | ypr[1] = asin(sinp); 40 | } 41 | 42 | // yaw (z-axis rotation) 43 | T siny_cosp = T(2) * (q[0] * q[3] + q[1] * q[2]); 44 | T cosy_cosp = T(1) - T(2) * (q[2] * q[2] + q[3] * q[3]); 45 | ypr[0] = atan2(siny_cosp, cosy_cosp); 46 | }; 47 | 48 | 49 | struct PitchRollFactor 50 | { 51 | PitchRollFactor(double p, double r, double q_var) 52 | : p(p), r(r), q_var(q_var) {} 53 | 54 | template 55 | bool operator()(const T* const q_i, T* residuals) const 56 | { 57 | T q_i_tmp[4]; 58 | q_i_tmp[0] = q_i[3]; // ceres in w, x, y, z order 59 | q_i_tmp[1] = q_i[0]; 60 | q_i_tmp[2] = q_i[1]; 61 | q_i_tmp[3] = q_i[2]; 62 | 63 | T ypr[3]; 64 | Quaternion2EulerAngle(q_i_tmp, ypr); 65 | 66 | T e[2]; 67 | e[0] = ypr[1] - T(p); 68 | e[1] = ypr[2] - T(r); 69 | 70 | residuals[0] = T(2) * e[0] / T(q_var); 71 | residuals[1] = T(2) * e[1] / T(q_var); 72 | 73 | return true; 74 | } 75 | 76 | static ceres::CostFunction* Create(const double p, const double r, const double q_var) 77 | { 78 | return (new ceres::AutoDiffCostFunction(new PitchRollFactor(p, r, q_var))); 79 | } 80 | 81 | double p, r; 82 | double q_var; 83 | }; 84 | 85 | 86 | 87 | struct GroundFactor 88 | { 89 | GroundFactor(double var, double tz_prev): var(var), tz_prev(tz_prev){} 90 | 91 | template 92 | bool operator()(const T* tz_curr, T* residuals) const 93 | { 94 | residuals[0] = (tz_curr[0] - tz_prev) / T(var); 95 | 96 | return true; 97 | } 98 | 99 | static ceres::CostFunction* Create(const double var, const double tz_prev) 100 | { 101 | return (new ceres::AutoDiffCostFunction(new GroundFactor(var, tz_prev))); 102 | } 103 | 104 | double var; 105 | double tz_prev; 106 | }; 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | -------------------------------------------------------------------------------- /C-LOAM/src/transformFusion.cpp: -------------------------------------------------------------------------------- 1 | /**************************************************************************************** 2 | * 3 | * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences 4 | * 5 | * Authors: Yanpeng Jia 6 | * Contact: jiayanpeng@sia.cn 7 | * 8 | ****************************************************************************************/ 9 | 10 | #include "util.h" 11 | 12 | class TransformFusion{ 13 | 14 | private: 15 | 16 | ros::NodeHandle nh; 17 | 18 | ros::Publisher pubLaserOdometry2; 19 | ros::Subscriber subLaserOdometry; 20 | ros::Subscriber subOdomAftMapped; 21 | 22 | 23 | nav_msgs::Odometry laserOdometry2; 24 | tf::StampedTransform laserOdometryTrans2; 25 | tf::TransformBroadcaster tfBroadcaster2; 26 | 27 | tf::StampedTransform map_2_camera_init_Trans; 28 | tf::TransformBroadcaster tfBroadcasterMap2CameraInit; 29 | 30 | tf::StampedTransform camera_2_base_link_Trans; 31 | tf::TransformBroadcaster tfBroadcasterCamera2Baselink; 32 | 33 | float transformSum[6]; 34 | float transformIncre[6]; 35 | float transformMapped[6]; 36 | float transformBefMapped[6]; 37 | float transformAftMapped[6]; 38 | 39 | std_msgs::Header currentHeader; 40 | 41 | public: 42 | 43 | TransformFusion(){ 44 | 45 | pubLaserOdometry2 = nh.advertise ("/integrated_to_init", 5); 46 | subLaserOdometry = nh.subscribe("/laser_odom_to_init", 5, &TransformFusion::laserOdometryHandler, this); 47 | subOdomAftMapped = nh.subscribe("/aft_mapped_to_init", 5, &TransformFusion::odomAftMappedHandler, this); 48 | 49 | laserOdometry2.header.frame_id = "camera_init"; 50 | laserOdometry2.child_frame_id = "camera"; 51 | 52 | laserOdometryTrans2.frame_id_ = "camera_init"; 53 | laserOdometryTrans2.child_frame_id_ = "camera"; 54 | 55 | map_2_camera_init_Trans.frame_id_ = "map"; 56 | map_2_camera_init_Trans.child_frame_id_ = "camera_init"; 57 | 58 | camera_2_base_link_Trans.frame_id_ = "camera"; 59 | camera_2_base_link_Trans.child_frame_id_ = "base_link"; 60 | 61 | for (int i = 0; i < 6; ++i) 62 | { 63 | transformSum[i] = 0; 64 | transformIncre[i] = 0; 65 | transformMapped[i] = 0; 66 | transformBefMapped[i] = 0; 67 | transformAftMapped[i] = 0; 68 | } 69 | } 70 | 71 | void transformAssociateToMap() 72 | { 73 | float x1 = cos(transformSum[1]) * (transformBefMapped[3] - transformSum[3]) 74 | - sin(transformSum[1]) * (transformBefMapped[5] - transformSum[5]); 75 | float y1 = transformBefMapped[4] - transformSum[4]; 76 | float z1 = sin(transformSum[1]) * (transformBefMapped[3] - transformSum[3]) 77 | + cos(transformSum[1]) * (transformBefMapped[5] - transformSum[5]); 78 | 79 | float x2 = x1; 80 | float y2 = cos(transformSum[0]) * y1 + sin(transformSum[0]) * z1; 81 | float z2 = -sin(transformSum[0]) * y1 + cos(transformSum[0]) * z1; 82 | 83 | transformIncre[3] = cos(transformSum[2]) * x2 + sin(transformSum[2]) * y2; 84 | transformIncre[4] = -sin(transformSum[2]) * x2 + cos(transformSum[2]) * y2; 85 | transformIncre[5] = z2; 86 | 87 | float sbcx = sin(transformSum[0]); 88 | float cbcx = cos(transformSum[0]); 89 | float sbcy = sin(transformSum[1]); 90 | float cbcy = cos(transformSum[1]); 91 | float sbcz = sin(transformSum[2]); 92 | float cbcz = cos(transformSum[2]); 93 | 94 | float sblx = sin(transformBefMapped[0]); 95 | float cblx = cos(transformBefMapped[0]); 96 | float sbly = sin(transformBefMapped[1]); 97 | float cbly = cos(transformBefMapped[1]); 98 | float sblz = sin(transformBefMapped[2]); 99 | float cblz = cos(transformBefMapped[2]); 100 | 101 | float salx = sin(transformAftMapped[0]); 102 | float calx = cos(transformAftMapped[0]); 103 | float saly = sin(transformAftMapped[1]); 104 | float caly = cos(transformAftMapped[1]); 105 | float salz = sin(transformAftMapped[2]); 106 | float calz = cos(transformAftMapped[2]); 107 | 108 | float srx = -sbcx*(salx*sblx + calx*cblx*salz*sblz + calx*calz*cblx*cblz) 109 | - cbcx*sbcy*(calx*calz*(cbly*sblz - cblz*sblx*sbly) 110 | - calx*salz*(cbly*cblz + sblx*sbly*sblz) + cblx*salx*sbly) 111 | - cbcx*cbcy*(calx*salz*(cblz*sbly - cbly*sblx*sblz) 112 | - calx*calz*(sbly*sblz + cbly*cblz*sblx) + cblx*cbly*salx); 113 | transformMapped[0] = -asin(srx); 114 | 115 | float srycrx = sbcx*(cblx*cblz*(caly*salz - calz*salx*saly) 116 | - cblx*sblz*(caly*calz + salx*saly*salz) + calx*saly*sblx) 117 | - cbcx*cbcy*((caly*calz + salx*saly*salz)*(cblz*sbly - cbly*sblx*sblz) 118 | + (caly*salz - calz*salx*saly)*(sbly*sblz + cbly*cblz*sblx) - calx*cblx*cbly*saly) 119 | + cbcx*sbcy*((caly*calz + salx*saly*salz)*(cbly*cblz + sblx*sbly*sblz) 120 | + (caly*salz - calz*salx*saly)*(cbly*sblz - cblz*sblx*sbly) + calx*cblx*saly*sbly); 121 | float crycrx = sbcx*(cblx*sblz*(calz*saly - caly*salx*salz) 122 | - cblx*cblz*(saly*salz + caly*calz*salx) + calx*caly*sblx) 123 | + cbcx*cbcy*((saly*salz + caly*calz*salx)*(sbly*sblz + cbly*cblz*sblx) 124 | + (calz*saly - caly*salx*salz)*(cblz*sbly - cbly*sblx*sblz) + calx*caly*cblx*cbly) 125 | - cbcx*sbcy*((saly*salz + caly*calz*salx)*(cbly*sblz - cblz*sblx*sbly) 126 | + (calz*saly - caly*salx*salz)*(cbly*cblz + sblx*sbly*sblz) - calx*caly*cblx*sbly); 127 | transformMapped[1] = atan2(srycrx / cos(transformMapped[0]), 128 | crycrx / cos(transformMapped[0])); 129 | 130 | float srzcrx = (cbcz*sbcy - cbcy*sbcx*sbcz)*(calx*salz*(cblz*sbly - cbly*sblx*sblz) 131 | - calx*calz*(sbly*sblz + cbly*cblz*sblx) + cblx*cbly*salx) 132 | - (cbcy*cbcz + sbcx*sbcy*sbcz)*(calx*calz*(cbly*sblz - cblz*sblx*sbly) 133 | - calx*salz*(cbly*cblz + sblx*sbly*sblz) + cblx*salx*sbly) 134 | + cbcx*sbcz*(salx*sblx + calx*cblx*salz*sblz + calx*calz*cblx*cblz); 135 | float crzcrx = (cbcy*sbcz - cbcz*sbcx*sbcy)*(calx*calz*(cbly*sblz - cblz*sblx*sbly) 136 | - calx*salz*(cbly*cblz + sblx*sbly*sblz) + cblx*salx*sbly) 137 | - (sbcy*sbcz + cbcy*cbcz*sbcx)*(calx*salz*(cblz*sbly - cbly*sblx*sblz) 138 | - calx*calz*(sbly*sblz + cbly*cblz*sblx) + cblx*cbly*salx) 139 | + cbcx*cbcz*(salx*sblx + calx*cblx*salz*sblz + calx*calz*cblx*cblz); 140 | transformMapped[2] = atan2(srzcrx / cos(transformMapped[0]), 141 | crzcrx / cos(transformMapped[0])); 142 | 143 | x1 = cos(transformMapped[2]) * transformIncre[3] - sin(transformMapped[2]) * transformIncre[4]; 144 | y1 = sin(transformMapped[2]) * transformIncre[3] + cos(transformMapped[2]) * transformIncre[4]; 145 | z1 = transformIncre[5]; 146 | 147 | x2 = x1; 148 | y2 = cos(transformMapped[0]) * y1 - sin(transformMapped[0]) * z1; 149 | z2 = sin(transformMapped[0]) * y1 + cos(transformMapped[0]) * z1; 150 | 151 | transformMapped[3] = transformAftMapped[3] 152 | - (cos(transformMapped[1]) * x2 + sin(transformMapped[1]) * z2); 153 | transformMapped[4] = transformAftMapped[4] - y2; 154 | transformMapped[5] = transformAftMapped[5] 155 | - (-sin(transformMapped[1]) * x2 + cos(transformMapped[1]) * z2); 156 | } 157 | 158 | void laserOdometryHandler(const nav_msgs::Odometry::ConstPtr& laserOdometry) 159 | { 160 | currentHeader = laserOdometry->header; 161 | 162 | double roll, pitch, yaw; 163 | geometry_msgs::Quaternion geoQuat = laserOdometry->pose.pose.orientation; 164 | tf::Matrix3x3(tf::Quaternion(geoQuat.z, -geoQuat.x, -geoQuat.y, geoQuat.w)).getRPY(roll, pitch, yaw); 165 | 166 | transformSum[0] = -pitch; 167 | transformSum[1] = -yaw; 168 | transformSum[2] = roll; 169 | 170 | transformSum[3] = laserOdometry->pose.pose.position.x; 171 | transformSum[4] = laserOdometry->pose.pose.position.y; 172 | transformSum[5] = laserOdometry->pose.pose.position.z; 173 | 174 | transformAssociateToMap(); 175 | 176 | geoQuat = tf::createQuaternionMsgFromRollPitchYaw 177 | (transformMapped[2], -transformMapped[0], -transformMapped[1]); 178 | 179 | laserOdometry2.header.stamp = laserOdometry->header.stamp; 180 | laserOdometry2.pose.pose.orientation.x = -geoQuat.y; 181 | laserOdometry2.pose.pose.orientation.y = -geoQuat.z; 182 | laserOdometry2.pose.pose.orientation.z = geoQuat.x; 183 | laserOdometry2.pose.pose.orientation.w = geoQuat.w; 184 | laserOdometry2.pose.pose.position.x = transformMapped[3]; 185 | laserOdometry2.pose.pose.position.y = transformMapped[4]; 186 | laserOdometry2.pose.pose.position.z = transformMapped[5]; 187 | pubLaserOdometry2.publish(laserOdometry2); 188 | 189 | laserOdometryTrans2.stamp_ = laserOdometry->header.stamp; 190 | laserOdometryTrans2.setRotation(tf::Quaternion(-geoQuat.y, -geoQuat.z, geoQuat.x, geoQuat.w)); 191 | laserOdometryTrans2.setOrigin(tf::Vector3(transformMapped[3], transformMapped[4], transformMapped[5])); 192 | tfBroadcaster2.sendTransform(laserOdometryTrans2); 193 | } 194 | 195 | void odomAftMappedHandler(const nav_msgs::Odometry::ConstPtr& odomAftMapped) 196 | { 197 | double roll, pitch, yaw; 198 | geometry_msgs::Quaternion geoQuat = odomAftMapped->pose.pose.orientation; 199 | tf::Matrix3x3(tf::Quaternion(geoQuat.z, -geoQuat.x, -geoQuat.y, geoQuat.w)).getRPY(roll, pitch, yaw); 200 | 201 | transformAftMapped[0] = -pitch; 202 | transformAftMapped[1] = -yaw; 203 | transformAftMapped[2] = roll; 204 | 205 | transformAftMapped[3] = odomAftMapped->pose.pose.position.x; 206 | transformAftMapped[4] = odomAftMapped->pose.pose.position.y; 207 | transformAftMapped[5] = odomAftMapped->pose.pose.position.z; 208 | 209 | transformBefMapped[0] = odomAftMapped->twist.twist.angular.x; 210 | transformBefMapped[1] = odomAftMapped->twist.twist.angular.y; 211 | transformBefMapped[2] = odomAftMapped->twist.twist.angular.z; 212 | 213 | transformBefMapped[3] = odomAftMapped->twist.twist.linear.x; 214 | transformBefMapped[4] = odomAftMapped->twist.twist.linear.y; 215 | transformBefMapped[5] = odomAftMapped->twist.twist.linear.z; 216 | } 217 | }; 218 | 219 | 220 | int main(int argc, char** argv) 221 | { 222 | ros::init(argc, argv, "c_loam"); 223 | 224 | TransformFusion TFusion; 225 | 226 | ROS_INFO("\033[1;32m---->\033[0m Transform Fusion Started."); 227 | 228 | ros::spin(); 229 | 230 | return 0; 231 | } 232 | -------------------------------------------------------------------------------- /Gemfile: -------------------------------------------------------------------------------- 1 | source "https://rubygems.org" 2 | 3 | # Hello! This is where you manage which Jekyll version is used to run. 4 | # When you want to use a different version, change it below, save the 5 | # file and run `bundle install`. Run Jekyll with `bundle exec`, like so: 6 | # 7 | # bundle exec jekyll serve 8 | # 9 | # This will help ensure the proper Jekyll version is running. 10 | # Happy Jekylling! 11 | 12 | gem "github-pages", group: :jekyll_plugins 13 | 14 | # If you want to use Jekyll native, uncomment the line below. 15 | # To upgrade, run `bundle update`. 16 | 17 | # gem "jekyll" 18 | 19 | gem "wdm", "~> 0.1.0" if Gem.win_platform? 20 | 21 | # If you have any plugins, put them here! 22 | group :jekyll_plugins do 23 | # gem "jekyll-archives" 24 | gem "jekyll-feed" 25 | gem 'jekyll-sitemap' 26 | gem 'hawkins' 27 | end 28 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # :dolls: C-LOAM: A Compact LiDAR Odometry and Mapping with Dynamic Removal 2 | 3 | The official implementation of C-LOAM (A Compact LiDAR Odometry and Mapping with Dynamic Removal), an accurate LiDAR odometry approach targeted for dynamic environments. C-LOAM achieve dynamic removal, ground extraction, and point cloud segmentation throught range image, showiing its compactedness. Additionally, we use ground points to estimate ground normal to impose ground contraints and feature submap to conduct loop closure detection. This work is accepted by IEEE ICUS 2024. 4 | 5 | Welcome to our [website](https://yaepiii.github.io/C-LOAM/) for more details. 6 | 7 | ![Video](./web/resources/C-LOAM.gif) 8 | 9 | If you think our work useful for your research, please cite: 10 | 11 | ``` 12 | @INPROCEEDINGS{10839822, 13 | author={Zhang, Meifeng and Jia, Yanpeng and Shao, Shiliang and Wang, Shiyi}, 14 | booktitle={2024 IEEE International Conference on Unmanned Systems (ICUS)}, 15 | title={A Compact LiDAR Odometry and Mapping with Dynamic Removal}, 16 | year={2024}, 17 | volume={}, 18 | number={}, 19 | pages={813-818}, 20 | keywords={Location awareness;Laser radar;Accuracy;Three-dimensional displays;Autonomous systems;Pose estimation;Feature extraction;Real-time systems;Odometry;Vehicle dynamics;Localization;Mapping;SLAM;Field Robots}, 21 | doi={10.1109/ICUS61736.2024.10839822}} 22 | 23 | ``` 24 | 25 | ## :mega: New 26 | 27 | - Oct. 19. 2024: :star: Commit the codes! 28 | - Aug. 20. 2024: :v: Paper is accepted by ICUS 2024! 29 | 30 | ## :gear: Installation 31 | 32 | ### Dependence 33 | 34 | Our system has been tested extensively on Ubuntu 20.04 Focal with ROS Noetic, although other versions may work. The following configuration with required dependencies has been verified to be compatible: 35 | 36 | - Ubuntu 20.04 37 | - ROS Noetic (roscpp, std_msgs, sensor_msgs, geometry_msgs, pcl_ros, jsk_recognition_msgs) 38 | - C++ 14 39 | - CMake >= 3.22.3 40 | - Point Cloud Library >= 1.10.0 41 | - Eigen >= 3.3.7 42 | - Ceres 1.14.0 43 | - GTSAM 4.0.3 44 | 45 | If you cannot compile successfully, you can uncomment the line 61 of `CMakeList.txt`, and replace it with your `GTSAM 4.0.3` installation path, such as: 46 | 47 | ``` 48 | set(GTSAM_DIR "/home/jyp/3rdparty/gtsam-4.0.3/build") #4.0.3 49 | ``` 50 | 51 | ### Building 52 | 53 | You can use the following command to build the project: 54 | 55 | ```bash 56 | #!/bin/bash 57 | source "/opt/ros/${ROS_DISTRO}/setup.bash" 58 | mkdir -p ~/catkin_ws/src 59 | cd ~/catkin_ws/src 60 | git clone git@github.com:Yaepiii/C-LOAM.git 61 | cd .. 62 | catkin_make 63 | ``` 64 | 65 | ## :snail: Run 66 | 67 | According to the dataset you want to test, you can modify the parameter values of `pointCloudTopic` in `util.h`. If an IMU is used, modify the parameter values of `imuTopic` in `util.h`. 68 | 69 | After sourcing the workspace, launch the C-LOAM ROS nodes via: 70 | 71 | ```bash 72 | #!/bin/bash 73 | # run C-LOAM node 74 | roslaunch c_loam run.launch 75 | 76 | # play your bag 77 | rosbag play your_test.bag --clock 78 | ``` 79 | 80 | ## :clipboard: Evaluation 81 | 82 | You can modify the pose file save path in line 232 of `mapOptmization.cpp` to save pose estimation results as TUM format, such that: 83 | 84 | ``` 85 | f_save_pose_evo.open("/home/jyp/3D_LiDAR_SLAM/pose_evo.txt", std::fstream::out); 86 | ``` 87 | 88 | ### Results 89 | 90 | ![localization](./web/resources/localization.png) 91 | 92 | ![dynamic_removal](./web/resources/dynamic_removal.png) 93 | 94 | ![ground_extraction](./web/resources/ground_extraction.png) 95 | 96 | ![loop_closure](./web/resources/loop_closure.png) 97 | 98 | For more results, please refer to our [paper](https://ieeexplore.ieee.org/abstract/document/10839822) 99 | 100 | ## :rose: Acknowledgements 101 | 102 | We thank the authors of the [LeGO-LOAM](https://github.com/RobustFieldAutonomyLab/LeGO-LOAM) and [SC-LeGO-LOAM](https://github.com/gisbi-kim/SC-LeGO-LOAM?tab=readme-ov-file) open-source packages: 103 | 104 | - . Shan and B. Englot, "LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain," 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 2018, pp. 4758-4765 105 | 106 | - G. Kim and A. Kim, "Scan Context: Egocentric Spatial Descriptor for Place Recognition Within 3D Point Cloud Map," 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 2018, pp. 4802-4809 107 | 108 | 109 | 110 | # Website License 111 | Creative Commons License
This work is licensed under a Creative Commons Attribution-ShareAlike 4.0 International License. 112 | -------------------------------------------------------------------------------- /cloud_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(cloud_msgs) 3 | 4 | 5 | find_package(catkin REQUIRED COMPONENTS 6 | message_generation 7 | geometry_msgs 8 | std_msgs 9 | nav_msgs 10 | ) 11 | 12 | add_message_files( 13 | DIRECTORY msg 14 | FILES 15 | cloud_info.msg 16 | ) 17 | 18 | generate_messages( 19 | DEPENDENCIES 20 | geometry_msgs 21 | std_msgs 22 | nav_msgs 23 | ) 24 | 25 | 26 | catkin_package( 27 | CATKIN_DEPENDS 28 | message_runtime 29 | message_generation 30 | geometry_msgs 31 | std_msgs 32 | nav_msgs 33 | ) 34 | 35 | include_directories( 36 | ${catkin_INCLUDE_DIRS} 37 | ) 38 | 39 | 40 | 41 | -------------------------------------------------------------------------------- /cloud_msgs/msg/cloud_info.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | 3 | int32[] startRingIndex 4 | int32[] endRingIndex 5 | 6 | float32 startOrientation 7 | float32 endOrientation 8 | float32 orientationDiff 9 | 10 | bool[] segmentedCloudGroundFlag # true - ground point, false - other points 11 | uint32[] segmentedCloudColInd # point column index in range image 12 | float32[] segmentedCloudRange # point range -------------------------------------------------------------------------------- /cloud_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | cloud_msgs 4 | 1.0.0 5 | The cloud_msgs package contains messages. 6 | 7 | Tixiao Shan 8 | 9 | BSD 10 | 11 | catkin 12 | geometry_msgs 13 | std_msgs 14 | message_runtime 15 | message_generation 16 | nav_msgs 17 | 18 | nav_msgs 19 | message_generation 20 | message_runtime 21 | geometry_msgs 22 | std_msgs 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /index.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 7 | 8 | 9 | C-LOAM 10 | 11 | 12 | 13 | 14 | 15 | 16 | 27 | 28 | 29 | 30 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 |
66 |
67 |
68 |
69 |
70 |

C-LOAM

71 |
72 |

A Compact LiDAR Odometry and Mapping with Dynamic Removal

73 | 74 |
75 |

2024 7th IEEE International Conference on Unmanned Systems

76 |
77 |
78 | 79 | Meifeng Zhang1 80 |      81 | 82 | Yanpeng Jia*2,3 83 |      84 | 85 | Shiliang Shao*2 86 |      87 | 88 | Shiyi Wang2 89 | 90 |
91 | 92 |
93 |

* corresponding author

94 |
95 |
96 | 1Baoding University     97 | 2Shenyang Institute of Automation     98 | 3University of Chinese Academy of Sciences     99 |
100 | 101 |
102 | 135 |
136 |
137 |
138 |
139 |
140 |
141 | 142 | 143 | 144 | 152 | 153 | 160 | 161 | 174 | 175 | 196 | 197 |
198 |
199 | 200 |
201 |
202 |

Abstract

203 |
204 |

205 | Real-time state estimation and mapping is a fundamental function 206 | of unmanned systems. In this paper, we propose 207 | a compact 3D Lidar odometry and mapping method (C-LOAM) 208 | for real-time 6-DOF pose estimation and map construction for 209 | unmanned ground vehicles. Our approach firstly remove dynamic 210 | objects from the environment by comparing differences between 211 | two consecutive range images. We then extract ground points 212 | from the range image. The remaining points are segmented in the 213 | range image to obtain robust feature points for the registration 214 | stage. After performing two-stage scan-matching, we use the extracted 215 | ground points to impose ground constraints and leverage 216 | the local feature submap for loop closure detection. By employing 217 | various data reuse strategies, we minimize memory consumption, 218 | creating a compact and accurate system. Experiments on multiple 219 | publicly available datasets demonstrate that our system provides 220 | more accurate localization and higher-quality maps compared to 221 | other state-of-the-art methods. 222 |

223 |
224 |
225 |
226 | 227 | 228 |
229 |
230 |

Video

231 |
232 | 234 |
235 |


236 |

237 | C-LOAM can efficiently remove dynamic objects, generating a cleaner map, and impose ground constraint through 238 | the proposed, simple, and accurate ground extraction method to refine pose estimation. 239 |

240 |
241 |
242 | 243 |
244 |
245 | 246 | 247 |
248 |
249 | 250 | 251 |
252 |
253 |

Method

254 | 255 |
256 | 257 |
258 |
259 |

260 | The system receives the 261 | raw point cloud from the Lidar as input and performs a 262 | spherical projection to obtain a range image. This range 263 | image is used for dynamic removal and efficient ground 264 | extraction. The remaining points are then segmented, and 265 | robust features are extracted for scan-to-scan registration. In 266 | the Mapping module, we use the spatial information of key 267 | frames to build local feature submaps and use the pose 268 | obtained from odometry as a prior for scan-to-map registration. 269 | The ground points Gk extracted from the front-end are used to 270 | impose ground constraints. Simultaneously, the local feature 271 | submap is reused for loop detection to correct the global pose. 272 | Finally, the global point cloud map and pose estimation are output. 273 |

274 | 275 |
276 |
277 | 278 | 279 |
280 |
281 | 282 | 283 | 302 | 303 |
304 |
305 | 306 |
307 |
308 |

Localization Evaluation

309 | 310 |
311 |

312 | Our method achieves the highest accuracy across all sequences evaluated. Among them, 313 | KITTI00 is an outdoor large-scale sequence with a total length of 3724m. Other methods 314 | exhibit significant drift that persist even with loop closure 315 | detection. In contrast, our approach achieves minimal drift 316 | of only 1.12 meters, benefiting ground constraints and a loop 317 | closure strategy based on local feature submap. Sequences like 318 | KITTI05 and KITTI07, which feature multiple dynamic vehicles posing challenges to localization, are effectively manage 319 | by our dynamic culling strategy. This approach successfully 320 | filters out dynamic effects, maintaining high accuracy in 321 | odometry estimation. 322 |

323 |
324 | 325 |
326 | 327 |
328 | 329 |
330 |

331 |
332 | 333 |
334 |
335 | 336 |
337 |
338 | 339 |
340 |
341 |

Mapping and Loop Closure Results

342 | 343 |

Dynamic Removal

344 |
345 |

346 | We compare the performance of 347 | our proposed method with LeGO-LOAM in mapping 348 | and dynamic object removal using the KITTI07 sequence. Our method utilizes a dynamic removal 349 | strategy based on range images to effectively mitigate the 350 | impact of dynamic objects in the environment and achieve 351 | clearer map construction. 352 |

353 |
354 | 355 |
356 | 357 |
358 | 359 |

Ground Extraction

360 |
361 |

362 | We demonstrate the benefits of our 363 | enhanced ground extraction method using the KITTI05 sequence. It is evident that LeGO-LOAM 364 | exhibits numerous false positives during ground extraction, 365 | whereas our proposed method effectively mitigates this issue 366 | and obtains more accurate ground points. This improvement 367 | forms a crucial foundation for registration and ground constraint application. 368 |

369 |
370 | 371 |
372 | 373 |
374 | 375 |

Loop Closure Detection

376 |
377 |

378 | SCLeGO-LOAM produces a large number of false detections, 379 | whereas our method ensures robust detection results. The local 380 | magnification figure shows SC-LeGO-LOAM results using 381 | the same parameters as our method. While using the same 382 | parameters reduces the number of false detections for SC-LeGO-LOAM, it also diminishes its ability to detect correct 383 | loops. Our method, benefiting from the large-scale properties 384 | of submap and the robustness of extracted features, effectively 385 | detects the correct loops. 386 |

387 |
388 | 389 |
390 | 391 |
392 | 393 |
394 |

395 |
396 | 397 |
398 |
399 | 400 |
401 |
402 | 403 |
404 |
405 |

Ablation Study

406 | 407 |
408 |

409 | Dynamic Removal: 410 | The comparisons between (a) and (f) 411 | demonstrate that the dynamic removal strategy enhances registration consistency, thereby improving localization accuracy. 412 | However, this does not bring much improvement, we analyze the reason is that KITI05 does not have too many dynamic 413 | objects, and the loop detection can correct for historical errors. 414 |

415 |

416 | Ground Extraction: 417 | From the comparisons between (b), (c), and (f), it is evident 418 | that applying ground constraints effectively suppresses drift, 419 | leading to a significant improvement in positioning accuracy. 420 | Additionally, our method enables more accurate ground point 421 | extraction compared to LeGO-LOAM ground extraction 422 | method. 423 |

424 |

425 | Loop Closure Detection: 426 | Interestingly, comparisons between (d), (e), and (f) reveal 427 | that our method achieves promising accuracy even without 428 | loop detection. Furthermore, loopback detection descriptors 429 | using local feature subgraphs are more effective and competitive than those using raw point clouds. 430 |

431 |
432 | 433 |
434 | 435 |
436 | 437 |
438 |

439 |
440 | 441 |
442 |
443 | 444 | 535 | 536 | 547 | 548 | 555 | 556 | 572 | 573 | 574 | 593 | 594 | 595 | 596 | -------------------------------------------------------------------------------- /run_server.sh: -------------------------------------------------------------------------------- 1 | bundle exec jekyll liveserve -------------------------------------------------------------------------------- /web/resources/C-LOAM.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/resources/C-LOAM.gif -------------------------------------------------------------------------------- /web/resources/ablation.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/resources/ablation.png -------------------------------------------------------------------------------- /web/resources/dynamic_removal.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/resources/dynamic_removal.png -------------------------------------------------------------------------------- /web/resources/ground_extraction.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/resources/ground_extraction.png -------------------------------------------------------------------------------- /web/resources/localization.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/resources/localization.png -------------------------------------------------------------------------------- /web/resources/loop_closure.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/resources/loop_closure.png -------------------------------------------------------------------------------- /web/resources/pipeline.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/resources/pipeline.png -------------------------------------------------------------------------------- /web/static/css/bulma-carousel.min.css: -------------------------------------------------------------------------------- 1 | @-webkit-keyframes spinAround{from{-webkit-transform:rotate(0);transform:rotate(0)}to{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}@keyframes spinAround{from{-webkit-transform:rotate(0);transform:rotate(0)}to{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}.slider{position:relative;width:100%}.slider-container{display:flex;flex-wrap:nowrap;flex-direction:row;overflow:hidden;-webkit-transform:translate3d(0,0,0);transform:translate3d(0,0,0);min-height:100%}.slider-container.is-vertical{flex-direction:column}.slider-container .slider-item{flex:none}.slider-container .slider-item .image.is-covered img{-o-object-fit:cover;object-fit:cover;-o-object-position:center center;object-position:center center;height:100%;width:100%}.slider-container .slider-item .video-container{height:0;padding-bottom:0;padding-top:56.25%;margin:0;position:relative}.slider-container .slider-item .video-container.is-1by1,.slider-container .slider-item .video-container.is-square{padding-top:100%}.slider-container .slider-item .video-container.is-4by3{padding-top:75%}.slider-container .slider-item .video-container.is-21by9{padding-top:42.857143%}.slider-container .slider-item .video-container embed,.slider-container .slider-item .video-container iframe,.slider-container .slider-item .video-container object{position:absolute;top:0;left:0;width:100%!important;height:100%!important}.slider-navigation-next,.slider-navigation-previous{display:flex;justify-content:center;align-items:center;position:absolute;width:42px;height:42px;background:#fff center center no-repeat;background-size:20px 20px;border:1px solid #fff;border-radius:25091983px;box-shadow:0 2px 5px #3232321a;top:50%;margin-top:-20px;left:0;cursor:pointer;transition:opacity .3s,-webkit-transform .3s;transition:transform .3s,opacity .3s;transition:transform .3s,opacity .3s,-webkit-transform .3s}.slider-navigation-next:hover,.slider-navigation-previous:hover{-webkit-transform:scale(1.2);transform:scale(1.2)}.slider-navigation-next.is-hidden,.slider-navigation-previous.is-hidden{display:none;opacity:0}.slider-navigation-next svg,.slider-navigation-previous svg{width:25%}.slider-navigation-next{left:auto;right:0;background:#fff center center no-repeat;background-size:20px 20px}.slider-pagination{display:none;justify-content:center;align-items:center;position:absolute;bottom:0;left:0;right:0;padding:.5rem 1rem;text-align:center}.slider-pagination .slider-page{background:#fff;width:10px;height:10px;border-radius:25091983px;display:inline-block;margin:0 3px;box-shadow:0 2px 5px #3232321a;transition:-webkit-transform .3s;transition:transform .3s;transition:transform .3s,-webkit-transform .3s;cursor:pointer}.slider-pagination .slider-page.is-active,.slider-pagination .slider-page:hover{-webkit-transform:scale(1.4);transform:scale(1.4)}@media screen and (min-width:800px){.slider-pagination{display:flex}}.hero.has-carousel{position:relative}.hero.has-carousel+.hero-body,.hero.has-carousel+.hero-footer,.hero.has-carousel+.hero-head{z-index:10;overflow:hidden}.hero.has-carousel .hero-carousel{position:absolute;top:0;left:0;bottom:0;right:0;height:auto;border:none;margin:auto;padding:0;z-index:0}.hero.has-carousel .hero-carousel .slider{width:100%;max-width:100%;overflow:hidden;height:100%!important;max-height:100%;z-index:0}.hero.has-carousel .hero-carousel .slider .has-background{max-height:100%}.hero.has-carousel .hero-carousel .slider .has-background .is-background{-o-object-fit:cover;object-fit:cover;-o-object-position:center center;object-position:center center;height:100%;width:100%}.hero.has-carousel .hero-body{margin:0 3rem;z-index:10} -------------------------------------------------------------------------------- /web/static/css/bulma-slider.min.css: -------------------------------------------------------------------------------- 1 | @-webkit-keyframes spinAround{from{-webkit-transform:rotate(0);transform:rotate(0)}to{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}@keyframes spinAround{from{-webkit-transform:rotate(0);transform:rotate(0)}to{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}input[type=range].slider{-webkit-appearance:none;-moz-appearance:none;appearance:none;margin:1rem 0;background:0 0;touch-action:none}input[type=range].slider.is-fullwidth{display:block;width:100%}input[type=range].slider:focus{outline:0}input[type=range].slider:not([orient=vertical])::-webkit-slider-runnable-track{width:100%}input[type=range].slider:not([orient=vertical])::-moz-range-track{width:100%}input[type=range].slider:not([orient=vertical])::-ms-track{width:100%}input[type=range].slider:not([orient=vertical]).has-output+output,input[type=range].slider:not([orient=vertical]).has-output-tooltip+output{width:3rem;background:#4a4a4a;border-radius:4px;padding:.4rem .8rem;font-size:.75rem;line-height:.75rem;text-align:center;text-overflow:ellipsis;white-space:nowrap;color:#fff;overflow:hidden;pointer-events:none;z-index:200}input[type=range].slider:not([orient=vertical]).has-output-tooltip:disabled+output,input[type=range].slider:not([orient=vertical]).has-output:disabled+output{opacity:.5}input[type=range].slider:not([orient=vertical]).has-output{display:inline-block;vertical-align:middle;width:calc(100% - (4.2rem))}input[type=range].slider:not([orient=vertical]).has-output+output{display:inline-block;margin-left:.75rem;vertical-align:middle}input[type=range].slider:not([orient=vertical]).has-output-tooltip{display:block}input[type=range].slider:not([orient=vertical]).has-output-tooltip+output{position:absolute;left:0;top:-.1rem}input[type=range].slider[orient=vertical]{-webkit-appearance:slider-vertical;-moz-appearance:slider-vertical;appearance:slider-vertical;-webkit-writing-mode:bt-lr;-ms-writing-mode:bt-lr;writing-mode:bt-lr}input[type=range].slider[orient=vertical]::-webkit-slider-runnable-track{height:100%}input[type=range].slider[orient=vertical]::-moz-range-track{height:100%}input[type=range].slider[orient=vertical]::-ms-track{height:100%}input[type=range].slider::-webkit-slider-runnable-track{cursor:pointer;animate:.2s;box-shadow:0 0 0 #7a7a7a;background:#dbdbdb;border-radius:4px;border:0 solid #7a7a7a}input[type=range].slider::-moz-range-track{cursor:pointer;animate:.2s;box-shadow:0 0 0 #7a7a7a;background:#dbdbdb;border-radius:4px;border:0 solid #7a7a7a}input[type=range].slider::-ms-track{cursor:pointer;animate:.2s;box-shadow:0 0 0 #7a7a7a;background:#dbdbdb;border-radius:4px;border:0 solid #7a7a7a}input[type=range].slider::-ms-fill-lower{background:#dbdbdb;border-radius:4px}input[type=range].slider::-ms-fill-upper{background:#dbdbdb;border-radius:4px}input[type=range].slider::-webkit-slider-thumb{box-shadow:none;border:1px solid #b5b5b5;border-radius:4px;background:#fff;cursor:pointer}input[type=range].slider::-moz-range-thumb{box-shadow:none;border:1px solid #b5b5b5;border-radius:4px;background:#fff;cursor:pointer}input[type=range].slider::-ms-thumb{box-shadow:none;border:1px solid #b5b5b5;border-radius:4px;background:#fff;cursor:pointer}input[type=range].slider::-webkit-slider-thumb{-webkit-appearance:none;appearance:none}input[type=range].slider.is-circle::-webkit-slider-thumb{border-radius:290486px}input[type=range].slider.is-circle::-moz-range-thumb{border-radius:290486px}input[type=range].slider.is-circle::-ms-thumb{border-radius:290486px}input[type=range].slider:active::-webkit-slider-thumb{-webkit-transform:scale(1.25);transform:scale(1.25)}input[type=range].slider:active::-moz-range-thumb{transform:scale(1.25)}input[type=range].slider:active::-ms-thumb{transform:scale(1.25)}input[type=range].slider:disabled{opacity:.5;cursor:not-allowed}input[type=range].slider:disabled::-webkit-slider-thumb{cursor:not-allowed;-webkit-transform:scale(1);transform:scale(1)}input[type=range].slider:disabled::-moz-range-thumb{cursor:not-allowed;transform:scale(1)}input[type=range].slider:disabled::-ms-thumb{cursor:not-allowed;transform:scale(1)}input[type=range].slider:not([orient=vertical]){min-height:calc((1rem + 2px) * 1.25)}input[type=range].slider:not([orient=vertical])::-webkit-slider-runnable-track{height:.5rem}input[type=range].slider:not([orient=vertical])::-moz-range-track{height:.5rem}input[type=range].slider:not([orient=vertical])::-ms-track{height:.5rem}input[type=range].slider[orient=vertical]::-webkit-slider-runnable-track{width:.5rem}input[type=range].slider[orient=vertical]::-moz-range-track{width:.5rem}input[type=range].slider[orient=vertical]::-ms-track{width:.5rem}input[type=range].slider::-webkit-slider-thumb{height:1rem;width:1rem}input[type=range].slider::-moz-range-thumb{height:1rem;width:1rem}input[type=range].slider::-ms-thumb{height:1rem;width:1rem}input[type=range].slider::-ms-thumb{margin-top:0}input[type=range].slider::-webkit-slider-thumb{margin-top:-.25rem}input[type=range].slider[orient=vertical]::-webkit-slider-thumb{margin-top:auto;margin-left:-.25rem}input[type=range].slider.is-small:not([orient=vertical]){min-height:calc((.75rem + 2px) * 1.25)}input[type=range].slider.is-small:not([orient=vertical])::-webkit-slider-runnable-track{height:.375rem}input[type=range].slider.is-small:not([orient=vertical])::-moz-range-track{height:.375rem}input[type=range].slider.is-small:not([orient=vertical])::-ms-track{height:.375rem}input[type=range].slider.is-small[orient=vertical]::-webkit-slider-runnable-track{width:.375rem}input[type=range].slider.is-small[orient=vertical]::-moz-range-track{width:.375rem}input[type=range].slider.is-small[orient=vertical]::-ms-track{width:.375rem}input[type=range].slider.is-small::-webkit-slider-thumb{height:.75rem;width:.75rem}input[type=range].slider.is-small::-moz-range-thumb{height:.75rem;width:.75rem}input[type=range].slider.is-small::-ms-thumb{height:.75rem;width:.75rem}input[type=range].slider.is-small::-ms-thumb{margin-top:0}input[type=range].slider.is-small::-webkit-slider-thumb{margin-top:-.1875rem}input[type=range].slider.is-small[orient=vertical]::-webkit-slider-thumb{margin-top:auto;margin-left:-.1875rem}input[type=range].slider.is-medium:not([orient=vertical]){min-height:calc((1.25rem + 2px) * 1.25)}input[type=range].slider.is-medium:not([orient=vertical])::-webkit-slider-runnable-track{height:.625rem}input[type=range].slider.is-medium:not([orient=vertical])::-moz-range-track{height:.625rem}input[type=range].slider.is-medium:not([orient=vertical])::-ms-track{height:.625rem}input[type=range].slider.is-medium[orient=vertical]::-webkit-slider-runnable-track{width:.625rem}input[type=range].slider.is-medium[orient=vertical]::-moz-range-track{width:.625rem}input[type=range].slider.is-medium[orient=vertical]::-ms-track{width:.625rem}input[type=range].slider.is-medium::-webkit-slider-thumb{height:1.25rem;width:1.25rem}input[type=range].slider.is-medium::-moz-range-thumb{height:1.25rem;width:1.25rem}input[type=range].slider.is-medium::-ms-thumb{height:1.25rem;width:1.25rem}input[type=range].slider.is-medium::-ms-thumb{margin-top:0}input[type=range].slider.is-medium::-webkit-slider-thumb{margin-top:-.3125rem}input[type=range].slider.is-medium[orient=vertical]::-webkit-slider-thumb{margin-top:auto;margin-left:-.3125rem}input[type=range].slider.is-large:not([orient=vertical]){min-height:calc((1.5rem + 2px) * 1.25)}input[type=range].slider.is-large:not([orient=vertical])::-webkit-slider-runnable-track{height:.75rem}input[type=range].slider.is-large:not([orient=vertical])::-moz-range-track{height:.75rem}input[type=range].slider.is-large:not([orient=vertical])::-ms-track{height:.75rem}input[type=range].slider.is-large[orient=vertical]::-webkit-slider-runnable-track{width:.75rem}input[type=range].slider.is-large[orient=vertical]::-moz-range-track{width:.75rem}input[type=range].slider.is-large[orient=vertical]::-ms-track{width:.75rem}input[type=range].slider.is-large::-webkit-slider-thumb{height:1.5rem;width:1.5rem}input[type=range].slider.is-large::-moz-range-thumb{height:1.5rem;width:1.5rem}input[type=range].slider.is-large::-ms-thumb{height:1.5rem;width:1.5rem}input[type=range].slider.is-large::-ms-thumb{margin-top:0}input[type=range].slider.is-large::-webkit-slider-thumb{margin-top:-.375rem}input[type=range].slider.is-large[orient=vertical]::-webkit-slider-thumb{margin-top:auto;margin-left:-.375rem}input[type=range].slider.is-white::-moz-range-track{background:#fff!important}input[type=range].slider.is-white::-webkit-slider-runnable-track{background:#fff!important}input[type=range].slider.is-white::-ms-track{background:#fff!important}input[type=range].slider.is-white::-ms-fill-lower{background:#fff}input[type=range].slider.is-white::-ms-fill-upper{background:#fff}input[type=range].slider.is-white .has-output-tooltip+output,input[type=range].slider.is-white.has-output+output{background-color:#fff;color:#0a0a0a}input[type=range].slider.is-black::-moz-range-track{background:#0a0a0a!important}input[type=range].slider.is-black::-webkit-slider-runnable-track{background:#0a0a0a!important}input[type=range].slider.is-black::-ms-track{background:#0a0a0a!important}input[type=range].slider.is-black::-ms-fill-lower{background:#0a0a0a}input[type=range].slider.is-black::-ms-fill-upper{background:#0a0a0a}input[type=range].slider.is-black .has-output-tooltip+output,input[type=range].slider.is-black.has-output+output{background-color:#0a0a0a;color:#fff}input[type=range].slider.is-light::-moz-range-track{background:#f5f5f5!important}input[type=range].slider.is-light::-webkit-slider-runnable-track{background:#f5f5f5!important}input[type=range].slider.is-light::-ms-track{background:#f5f5f5!important}input[type=range].slider.is-light::-ms-fill-lower{background:#f5f5f5}input[type=range].slider.is-light::-ms-fill-upper{background:#f5f5f5}input[type=range].slider.is-light .has-output-tooltip+output,input[type=range].slider.is-light.has-output+output{background-color:#f5f5f5;color:#363636}input[type=range].slider.is-dark::-moz-range-track{background:#363636!important}input[type=range].slider.is-dark::-webkit-slider-runnable-track{background:#363636!important}input[type=range].slider.is-dark::-ms-track{background:#363636!important}input[type=range].slider.is-dark::-ms-fill-lower{background:#363636}input[type=range].slider.is-dark::-ms-fill-upper{background:#363636}input[type=range].slider.is-dark .has-output-tooltip+output,input[type=range].slider.is-dark.has-output+output{background-color:#363636;color:#f5f5f5}input[type=range].slider.is-primary::-moz-range-track{background:#00d1b2!important}input[type=range].slider.is-primary::-webkit-slider-runnable-track{background:#00d1b2!important}input[type=range].slider.is-primary::-ms-track{background:#00d1b2!important}input[type=range].slider.is-primary::-ms-fill-lower{background:#00d1b2}input[type=range].slider.is-primary::-ms-fill-upper{background:#00d1b2}input[type=range].slider.is-primary .has-output-tooltip+output,input[type=range].slider.is-primary.has-output+output{background-color:#00d1b2;color:#fff}input[type=range].slider.is-link::-moz-range-track{background:#3273dc!important}input[type=range].slider.is-link::-webkit-slider-runnable-track{background:#3273dc!important}input[type=range].slider.is-link::-ms-track{background:#3273dc!important}input[type=range].slider.is-link::-ms-fill-lower{background:#3273dc}input[type=range].slider.is-link::-ms-fill-upper{background:#3273dc}input[type=range].slider.is-link .has-output-tooltip+output,input[type=range].slider.is-link.has-output+output{background-color:#3273dc;color:#fff}input[type=range].slider.is-info::-moz-range-track{background:#209cee!important}input[type=range].slider.is-info::-webkit-slider-runnable-track{background:#209cee!important}input[type=range].slider.is-info::-ms-track{background:#209cee!important}input[type=range].slider.is-info::-ms-fill-lower{background:#209cee}input[type=range].slider.is-info::-ms-fill-upper{background:#209cee}input[type=range].slider.is-info .has-output-tooltip+output,input[type=range].slider.is-info.has-output+output{background-color:#209cee;color:#fff}input[type=range].slider.is-success::-moz-range-track{background:#23d160!important}input[type=range].slider.is-success::-webkit-slider-runnable-track{background:#23d160!important}input[type=range].slider.is-success::-ms-track{background:#23d160!important}input[type=range].slider.is-success::-ms-fill-lower{background:#23d160}input[type=range].slider.is-success::-ms-fill-upper{background:#23d160}input[type=range].slider.is-success .has-output-tooltip+output,input[type=range].slider.is-success.has-output+output{background-color:#23d160;color:#fff}input[type=range].slider.is-warning::-moz-range-track{background:#ffdd57!important}input[type=range].slider.is-warning::-webkit-slider-runnable-track{background:#ffdd57!important}input[type=range].slider.is-warning::-ms-track{background:#ffdd57!important}input[type=range].slider.is-warning::-ms-fill-lower{background:#ffdd57}input[type=range].slider.is-warning::-ms-fill-upper{background:#ffdd57}input[type=range].slider.is-warning .has-output-tooltip+output,input[type=range].slider.is-warning.has-output+output{background-color:#ffdd57;color:rgba(0,0,0,.7)}input[type=range].slider.is-danger::-moz-range-track{background:#ff3860!important}input[type=range].slider.is-danger::-webkit-slider-runnable-track{background:#ff3860!important}input[type=range].slider.is-danger::-ms-track{background:#ff3860!important}input[type=range].slider.is-danger::-ms-fill-lower{background:#ff3860}input[type=range].slider.is-danger::-ms-fill-upper{background:#ff3860}input[type=range].slider.is-danger .has-output-tooltip+output,input[type=range].slider.is-danger.has-output+output{background-color:#ff3860;color:#fff} -------------------------------------------------------------------------------- /web/static/css/dics.original.css: -------------------------------------------------------------------------------- 1 | .b-dics { 2 | width : 100%; 3 | max-width : 100%; 4 | position : relative; 5 | overflow : hidden; 6 | display : flex; 7 | opacity : 0; 8 | } 9 | 10 | .b-dics__section { 11 | height : 100%; 12 | } 13 | 14 | .b-dics__slider:hover :before { 15 | color : #FFFFFF; 16 | border-color : #FFFFFF; 17 | } 18 | 19 | .b-dics__text { 20 | position : absolute; 21 | top : 0; 22 | left : 50%; 23 | padding : 5px 25px; 24 | transform : translateX(-50%); 25 | background : #FFFFFF; 26 | z-index : 11; 27 | font-family : Arial, serif; 28 | color : #3d3d3d; 29 | user-select : none; 30 | font-size : 13px; 31 | text-align : center; 32 | margin : 16px 0; 33 | white-space : nowrap; 34 | opacity : .7; 35 | pointer-events : none; 36 | } 37 | 38 | .b-dics__image-container { 39 | width : 100%; 40 | height : 100%; 41 | display : block; 42 | overflow : hidden; 43 | position : relative; 44 | } 45 | 46 | .b-dics__image { 47 | height : 100%; 48 | position : absolute; 49 | left : 0; 50 | top : 50%; 51 | transform : translateY(-50%); 52 | user-select : none; 53 | max-width : none; 54 | } 55 | 56 | .b-dics__slider { 57 | color : #FFFFFF; 58 | position : absolute; 59 | left : 100%; 60 | top : 0; 61 | cursor : pointer; 62 | transform : translateX(-50%); 63 | height : 100%; 64 | width : 3px; 65 | padding : 0 30px; 66 | z-index : 1; 67 | touch-action : none; 68 | line-height : normal; 69 | opacity : .7; 70 | } 71 | 72 | .b-dics__slider:before { 73 | content : ''; 74 | -webkit-mask : url(data:image/svg+xml;base64,PD94bWwgdmVyc2lvbj0iMS4wIiBlbmNvZGluZz0idXRmLTgiPz48c3ZnIHZlcnNpb249IjEuMSIgaWQ9IkxheWVyXzEiIHhtbG5zPSJodHRwOi8vd3d3LnczLm9yZy8yMDAwL3N2ZyIgeG1sbnM6eGxpbms9Imh0dHA6Ly93d3cudzMub3JnLzE5OTkveGxpbmsiIHg9IjBweCIgeT0iMHB4IiB2aWV3Qm94PSIwIDAgNTEyIDUxMiIgc3R5bGU9ImVuYWJsZS1iYWNrZ3JvdW5kOm5ldyAwIDAgNTEyIDUxMjsiIHhtbDpzcGFjZT0icHJlc2VydmUiPjxzdHlsZSB0eXBlPSJ0ZXh0L2NzcyI+LnN0MHtmaWxsOiNGRkZGRkY7ZW5hYmxlLWJhY2tncm91bmQ6bmV3ICAgIDt9PC9zdHlsZT48cGF0aCBjbGFzcz0ic3QwIiBkPSJNMTgwLjIsMTA4LjFsNjEuNy02Mi4yYzMuOC0zLjgsOC44LTUuOSwxNC4xLTUuOWM1LjMsMCwxMC40LDIuMSwxNC4xLDUuOWw2MS43LDYyLjJjMy45LDMuOSw5LjEsNS45LDE0LjIsNS45czEwLjItMS45LDE0LjEtNS44YzcuOC03LjgsNy45LTIwLjQsMC4xLTI4LjNsLTYxLjctNjIuMkMyODcuMiw2LjMsMjcyLjEsMCwyNTYsMHMtMzEuMiw2LjMtNDIuNSwxNy44TDE1MS44LDgwYy03LjgsNy44LTcuNywyMC41LDAuMSwyOC4zQzE1OS44LDExNiwxNzIuNCwxMTUuOSwxODAuMiwxMDguMXoiLz48cGF0aCBjbGFzcz0ic3QwIiBkPSJNMzMxLjgsNDAzLjlsLTYxLjcsNjIuMmMtMy44LDMuOC04LjgsNS45LTE0LjEsNS45Yy01LjMsMC0xMC40LTIuMS0xNC4xLTUuOWwtNjEuNy02Mi4yYy03LjgtNy44LTIwLjQtNy45LTI4LjMtMC4xYy03LjgsNy44LTcuOSwyMC40LTAuMSwyOC4zbDYxLjcsNjIuMmMxMS40LDExLjQsMjYuNSwxNy44LDQyLjUsMTcuOHMzMS4yLTYuMyw0Mi41LTE3LjhsNjEuNy02Mi4yYzcuOC03LjgsNy43LTIwLjUtMC4xLTI4LjNDMzUyLjIsMzk2LDMzOS42LDM5Ni4xLDMzMS44LDQwMy45eiIvPjwvc3ZnPg==) no-repeat 100% 100%; 75 | mask : url(data:image/svg+xml;base64,PD94bWwgdmVyc2lvbj0iMS4wIiBlbmNvZGluZz0idXRmLTgiPz48c3ZnIHZlcnNpb249IjEuMSIgaWQ9IkxheWVyXzEiIHhtbG5zPSJodHRwOi8vd3d3LnczLm9yZy8yMDAwL3N2ZyIgeG1sbnM6eGxpbms9Imh0dHA6Ly93d3cudzMub3JnLzE5OTkveGxpbmsiIHg9IjBweCIgeT0iMHB4IiB2aWV3Qm94PSIwIDAgNTEyIDUxMiIgc3R5bGU9ImVuYWJsZS1iYWNrZ3JvdW5kOm5ldyAwIDAgNTEyIDUxMjsiIHhtbDpzcGFjZT0icHJlc2VydmUiPjxzdHlsZSB0eXBlPSJ0ZXh0L2NzcyI+LnN0MHtmaWxsOiNGRkZGRkY7ZW5hYmxlLWJhY2tncm91bmQ6bmV3ICAgIDt9PC9zdHlsZT48cGF0aCBjbGFzcz0ic3QwIiBkPSJNMTgwLjIsMTA4LjFsNjEuNy02Mi4yYzMuOC0zLjgsOC44LTUuOSwxNC4xLTUuOWM1LjMsMCwxMC40LDIuMSwxNC4xLDUuOWw2MS43LDYyLjJjMy45LDMuOSw5LjEsNS45LDE0LjIsNS45czEwLjItMS45LDE0LjEtNS44YzcuOC03LjgsNy45LTIwLjQsMC4xLTI4LjNsLTYxLjctNjIuMkMyODcuMiw2LjMsMjcyLjEsMCwyNTYsMHMtMzEuMiw2LjMtNDIuNSwxNy44TDE1MS44LDgwYy03LjgsNy44LTcuNywyMC41LDAuMSwyOC4zQzE1OS44LDExNiwxNzIuNCwxMTUuOSwxODAuMiwxMDguMXoiLz48cGF0aCBjbGFzcz0ic3QwIiBkPSJNMzMxLjgsNDAzLjlsLTYxLjcsNjIuMmMtMy44LDMuOC04LjgsNS45LTE0LjEsNS45Yy01LjMsMC0xMC40LTIuMS0xNC4xLTUuOWwtNjEuNy02Mi4yYy03LjgtNy44LTIwLjQtNy45LTI4LjMtMC4xYy03LjgsNy44LTcuOSwyMC40LTAuMSwyOC4zbDYxLjcsNjIuMmMxMS40LDExLjQsMjYuNSwxNy44LDQyLjUsMTcuOHMzMS4yLTYuMyw0Mi41LTE3LjhsNjEuNy02Mi4yYzcuOC03LjgsNy43LTIwLjUtMC4xLTI4LjNDMzUyLjIsMzk2LDMzOS42LDM5Ni4xLDMzMS44LDQwMy45eiIvPjwvc3ZnPg==) no-repeat 100% 100%; 76 | mask-size : cover; 77 | -webkit-mask-size : cover; 78 | width : 26px; 79 | height : 26px; 80 | padding : 0; 81 | background-color : currentColor; 82 | position : absolute; 83 | top : 50%; 84 | left : 50%; 85 | transform : translate(-50%, -50%) rotate(90deg); 86 | z-index : 2; 87 | font-size : 0; 88 | } 89 | 90 | .b-dics__slider:after { 91 | content : ''; 92 | position : absolute; 93 | left : 50%; 94 | top : 0; 95 | transform : translateX(-50%); 96 | height : 100%; 97 | width : 3px; 98 | background-color : currentColor; 99 | z-index : 1; 100 | } 101 | 102 | .b-dics__image-container:hover .b-dics__text { 103 | opacity : 1; 104 | } 105 | 106 | .b-dics__slider:hover { 107 | opacity : 1; 108 | } 109 | 110 | /* Text Position 111 | ****************************************************************************/ 112 | 113 | .b-dics--tp-center .b-dics__text { 114 | top : 50%; 115 | transform : translate(-50%, -50%); 116 | margin : 0; 117 | } 118 | 119 | .b-dics--tp-bottom .b-dics__text { 120 | top : initial; 121 | bottom : 0; 122 | transform : translate(-50%, -50%); 123 | } 124 | 125 | .b-dics--tp-left .b-dics__text { 126 | left : 0; 127 | top : 50%; 128 | transform : translateY(-50%); 129 | margin : 0 16px; 130 | } 131 | 132 | .b-dics--tp-right .b-dics__text { 133 | left : initial; 134 | right : 0; 135 | top : 50%; 136 | transform : translateY(-50%); 137 | margin : 0 16px; 138 | } 139 | 140 | /* Hide texts 141 | ****************************************************************************/ 142 | 143 | .b-dics--hide-texts .b-dics__text { 144 | background : #ffffff; 145 | opacity : 0; 146 | } 147 | 148 | .b-dics--hide-texts .b-dics__image-container:hover .b-dics__text { 149 | opacity : 1; 150 | } 151 | 152 | /* Vertical Sliders 153 | ****************************************************************************/ 154 | 155 | .b-dics--vertical { 156 | flex-direction : column; 157 | } 158 | 159 | .b-dics--vertical .b-dics__section { 160 | height : auto; 161 | width : 100%; 162 | } 163 | 164 | .b-dics--vertical .b-dics__image { 165 | left : 50%; 166 | transform : translateX(-50%); 167 | top : 0; 168 | width : 100%; 169 | height : auto; 170 | } 171 | 172 | .b-dics--vertical .b-dics__slider { 173 | top : 100%; 174 | transform : translateY(-50%); 175 | width : 100%; 176 | height : 3px; 177 | padding : 30px 0; 178 | left : 0; 179 | } 180 | 181 | .b-dics--vertical .b-dics__slider:after { 182 | top : 50%; 183 | left : 0; 184 | transform : translateY(-50%); 185 | width : 100%; 186 | height : 3px; 187 | } 188 | 189 | .b-dics--vertical .b-dics__slider:before { 190 | transform : translate(-50%, -50%); 191 | } -------------------------------------------------------------------------------- /web/static/css/index.css: -------------------------------------------------------------------------------- 1 | body { 2 | font-family: 'Noto Sans', sans-serif; 3 | } 4 | 5 | 6 | .footer .icon-link { 7 | font-size: 25px; 8 | color: #000; 9 | } 10 | 11 | .link-block a { 12 | margin-top: 5px; 13 | margin-bottom: 5px; 14 | } 15 | 16 | .dnerf { 17 | font-variant: small-caps; 18 | } 19 | 20 | 21 | .teaser .hero-body { 22 | padding-top: 0; 23 | padding-bottom: 3rem; 24 | } 25 | 26 | .teaser { 27 | font-family: 'Google Sans', sans-serif; 28 | } 29 | 30 | 31 | .publication-title { 32 | } 33 | 34 | .publication-banner { 35 | max-height: parent; 36 | 37 | } 38 | 39 | .publication-banner video { 40 | position: relative; 41 | left: auto; 42 | top: auto; 43 | transform: none; 44 | object-fit: fit; 45 | } 46 | 47 | .publication-header .hero-body { 48 | } 49 | 50 | .publication-title { 51 | font-family: 'Google Sans', sans-serif; 52 | } 53 | 54 | .publication-authors { 55 | font-family: 'Google Sans', sans-serif; 56 | } 57 | 58 | .publication-venue { 59 | color: #555; 60 | width: fit-content; 61 | font-weight: bold; 62 | } 63 | 64 | .publication-awards { 65 | color: #ff3860; 66 | width: fit-content; 67 | font-weight: bolder; 68 | } 69 | 70 | .publication-authors { 71 | } 72 | 73 | .publication-authors a { 74 | color: hsl(204, 86%, 53%) !important; 75 | } 76 | 77 | .publication-authors a:hover { 78 | text-decoration: underline; 79 | } 80 | 81 | .author-block { 82 | display: inline-block; 83 | } 84 | 85 | .publication-banner img { 86 | } 87 | 88 | .publication-authors { 89 | /*color: #4286f4;*/ 90 | } 91 | 92 | .publication-video { 93 | position: relative; 94 | width: 100%; 95 | height: 0; 96 | padding-bottom: 56.25%; 97 | 98 | overflow: hidden; 99 | border-radius: 10px !important; 100 | } 101 | 102 | .publication-video iframe { 103 | position: absolute; 104 | top: 0; 105 | left: 0; 106 | width: 100%; 107 | height: 100%; 108 | } 109 | 110 | .publication-body img { 111 | } 112 | 113 | .results-carousel { 114 | overflow: hidden; 115 | } 116 | 117 | .results-carousel .item { 118 | margin: 5px; 119 | overflow: hidden; 120 | border: 1px solid #bbb; 121 | border-radius: 10px; 122 | padding: 0; 123 | font-size: 0; 124 | } 125 | 126 | .results-carousel video { 127 | margin: 0; 128 | } 129 | 130 | 131 | .interpolation-panel { 132 | background: #f5f5f5; 133 | border-radius: 10px; 134 | } 135 | 136 | .interpolation-panel .interpolation-image { 137 | width: 100%; 138 | border-radius: 5px; 139 | } 140 | 141 | .interpolation-video-column { 142 | } 143 | 144 | .interpolation-panel .slider { 145 | margin: 0 !important; 146 | } 147 | 148 | .interpolation-panel .slider { 149 | margin: 0 !important; 150 | } 151 | 152 | #interpolation-image-wrapper { 153 | width: 100%; 154 | } 155 | #interpolation-image-wrapper img { 156 | border-radius: 5px; 157 | } 158 | 159 | /* for recon list */ 160 | li { 161 | cursor: pointer; 162 | } 163 | 164 | /* Style the buttons that are used to open the tab content */ 165 | .nav-item { 166 | overflow: hidden; 167 | text-align: center; 168 | width: 100%; 169 | background-color: inherit; 170 | float: left; 171 | border: 1px solid #ddd; 172 | outline: none; 173 | cursor: pointer; 174 | transition: 0.0s; 175 | border-top-right-radius: 10px; 176 | border-top-left-radius: 10px; 177 | } 178 | 179 | /* Change background color of buttons on hover */ 180 | .nav-item:hover { 181 | background-color: #c7dc94; 182 | } 183 | 184 | /* Create an active/current tablink class */ 185 | .nav-tabs .nav-link.active { 186 | background-color: #5c7f17; 187 | color:white; 188 | font-weight: 500; 189 | } 190 | 191 | .nav a { 192 | color: #000; 193 | text-decoration: none; 194 | } 195 | .nav a:hover { 196 | color: #000; 197 | font-weight: 500; 198 | text-decoration: none; 199 | } 200 | 201 | .b-dics__slider { 202 | color: #f0f0f0; 203 | } 204 | .b-dics__slider:after { 205 | width: 2px; 206 | } 207 | 208 | /* Go from zero to full opacity */ 209 | @keyframes fadeEffect { 210 | from {opacity: 0;} 211 | to {opacity: 1;} 212 | } 213 | 214 | .content-row { 215 | padding-left: 10px; 216 | padding-right: 10px; 217 | padding-top: 10px; 218 | padding-bottom: 10px; 219 | display: flex; 220 | flex-direction: row; 221 | flex-wrap: wrap; 222 | text-align: center; 223 | } 224 | 225 | .demo-scene-panel { 226 | margin-top: 10px; 227 | margin-bottom: 10px; 228 | padding: 10px; 229 | color: #111111; 230 | border-radius: 7px; 231 | border: #bbbbbb 1px solid; 232 | background-color: #f1f1f1; 233 | width: 220px; 234 | margin-left: 8px; 235 | margin-right: 8px; 236 | } -------------------------------------------------------------------------------- /web/static/css/style.css: -------------------------------------------------------------------------------- 1 | body { 2 | font-family: IBM Plex Sans, sans-serif; 3 | padding-bottom: 50px; 4 | font-size: 100%; 5 | line-height: 1.3em; 6 | letter-spacing: -0.1pt; 7 | hyphens: auto; 8 | -ms-hyphens: auto; 9 | -webkit-hyphens: auto; 10 | } 11 | 12 | a { 13 | color: #11a1c0; 14 | font-weight: 500; 15 | text-decoration: none; 16 | } 17 | a:hover { 18 | color: #006d85; 19 | font-style: normal; 20 | text-decoration: underline; 21 | } 22 | 23 | #banner { 24 | padding: 30px 0 0 0; 25 | background-image: linear-gradient(#000000, #414d28); 26 | box-shadow: 0 0 15px 30px #414d28; 27 | } 28 | 29 | .jumbotron { 30 | color: #dddddd; 31 | } 32 | .jumbotron a { 33 | color: #41c793; 34 | } 35 | .jumbotron a:hover { 36 | color: #00ff9c; 37 | } 38 | 39 | #main a:hover { 40 | font-weight: 600; 41 | text-decoration: underline; 42 | } 43 | 44 | p { 45 | text-align: justify; 46 | } 47 | 48 | hr { 49 | background: #80808083; 50 | margin: 30px 0 20px 0; 51 | padding: 1px 0 0 0; 52 | max-width: 1000px; 53 | } 54 | 55 | .jumbotron .btn-primary { 56 | font-size: 110%; 57 | color: #fff; 58 | background-color: #4a6a0c; 59 | border-color: #7b953b; 60 | border-width: 3px; 61 | margin: 0 5px 0 0; 62 | } 63 | .jumbotron .btn-primary:hover { 64 | color: #fff; 65 | background-color: #5c7f17; 66 | border-color: #c7dc94; 67 | font-weight: 500; 68 | } 69 | .jumbotron .btn-primary:active:hover { 70 | background-color: #78a130; 71 | border-color: #caff6e; 72 | } 73 | 74 | .jumbotron .btn-primary1 { 75 | font-size: 110%; 76 | color: #fff; 77 | background-color: #877408; 78 | border-color: #ffd903; 79 | border-width: 3px; 80 | margin: 0 5px 0 0; 81 | } 82 | .jumbotron .btn-primary1:hover { 83 | color: #fff; 84 | background-color: #ab930e; 85 | border-color: #ffed8a; 86 | font-weight: 500; 87 | } 88 | .jumbotron .btn-primary1:active:hover { 89 | background-color: #ccb016; 90 | border-color: #fcf1b3; 91 | } 92 | 93 | h2 { 94 | font-size: 170%; 95 | font-weight: 600; 96 | padding: 0 20px 0 20px; 97 | } 98 | #name { 99 | font-size: 120%; 100 | font-weight: 700; 101 | background: linear-gradient(to bottom, #cfc09f 22%, #634f2c 24%, #cfc09f 26%, #cfc09f 27%, #ffecb3 40%,#6a4c2f 78%); 102 | -webkit-background-clip: text; 103 | -webkit-text-fill-color: transparent; 104 | } 105 | h5 { 106 | text-align: center; 107 | font-size: 150%; 108 | font-weight: 600; 109 | padding: 10px 0 10px 0; 110 | } 111 | .author { 112 | font-size: 110%; 113 | font-weight: 500; 114 | margin: 0 0 3px 0; 115 | padding: 0 0 0 0; 116 | } 117 | .row-author { 118 | margin: 0 70px 0 70px; 119 | } 120 | h9 { 121 | font-size: 90%; 122 | color: #999999; 123 | } 124 | 125 | .container { 126 | max-width: 1000px; 127 | padding: 0 20px 0 20px; 128 | } 129 | 130 | .all-center { 131 | position: absolute; 132 | top: 50%; 133 | left: 50%; 134 | -ms-transform: translateY(-50%) translateX(-50%); 135 | transform: translateY(-50%) translateX(-50%); 136 | } 137 | 138 | #title { 139 | font-size: 105%; 140 | padding: 0 0 10px 0; 141 | } 142 | #affiliation { 143 | font-weight: 400; 144 | font-size: 110%; 145 | color: #96d428; 146 | padding: 15px 0 5px 0; 147 | } 148 | #venue { 149 | font-weight: 400; 150 | font-size: 110%; 151 | color: #FF5; 152 | margin: 10px auto 10px auto; 153 | padding: 0 20px 0 20px; 154 | } 155 | #venue b { font-weight: 600; } 156 | #highlight { 157 | line-height: 1.5em; 158 | font-weight: 600; 159 | font-size: 130%; 160 | color: #FFF; 161 | text-shadow: 0px 0px 10px #FFF; 162 | } 163 | #pitch { 164 | font-weight: 400; 165 | font-size: 105%; 166 | max-width: 745px; 167 | color: #EEE; 168 | margin: 20px auto 0 auto; 169 | } 170 | #inquiries { 171 | font-weight: 400; 172 | font-size: 100%; 173 | color: #f5a82e; 174 | max-width: 820px; 175 | margin: 10px auto 0 auto; 176 | } 177 | #inquiries a { color: #0E8; } 178 | #inquiries a:hover { color: #4FB; } 179 | 180 | .buttons { 181 | padding: 10px 0 0 0; 182 | } 183 | 184 | .column-2 { 185 | position: relative; 186 | float: left; 187 | width: 50%; 188 | } 189 | .column-3 { 190 | position: relative; 191 | float: left; 192 | width: 32%; 193 | margin: 0 0 15px 0; 194 | } 195 | .column-4 { 196 | position: relative; 197 | float: left; 198 | width: 25%; 199 | height: 220px; 200 | } 201 | 202 | .enlarge { 203 | padding-bottom: 10px; 204 | margin: auto; 205 | } 206 | 207 | .row:after { 208 | content: ""; 209 | display: table; 210 | clear: both; 211 | } 212 | 213 | .large_video { 214 | margin: 10px 0 0 0; 215 | border: 1px solid #BBB; 216 | box-shadow: 0 0 30px #792; 217 | } 218 | 219 | h6 { 220 | font-size: 105%; 221 | font-weight: 600; 222 | } 223 | .approach_video { 224 | margin: 30px 0 20px 0; 225 | border: 1px solid #BBB; 226 | box-shadow: 0 0 30px #792; 227 | } 228 | .approach_text { 229 | margin-left: 23px; 230 | text-align: justify; 231 | } 232 | 233 | #citation { 234 | line-height: 1.1em; 235 | max-width: 750px; 236 | letter-spacing: 0pt; 237 | font: 95% "Inconsolata"; 238 | border: 2px solid #666; 239 | margin: 20px auto 20px auto; 240 | padding: 15px 15px 15px 15px; 241 | box-shadow: 0 0 10px #FAF; 242 | } 243 | 244 | /* for recon list */ 245 | li { 246 | cursor: pointer; 247 | } 248 | 249 | /* Style the buttons that are used to open the tab content */ 250 | .nav-item { 251 | overflow: hidden; 252 | text-align: center; 253 | width: 100%; 254 | background-color: inherit; 255 | float: left; 256 | border: 1px solid #ddd; 257 | outline: none; 258 | cursor: pointer; 259 | transition: 0.0s; 260 | border-top-right-radius: 10px; 261 | border-top-left-radius: 10px; 262 | } 263 | 264 | /* Change background color of buttons on hover */ 265 | .nav-item:hover { 266 | background-color: #c7dc94; 267 | } 268 | 269 | /* Create an active/current tablink class */ 270 | .nav-tabs .nav-link.active { 271 | background-color: #5c7f17; 272 | color:white; 273 | font-weight: 500; 274 | } 275 | 276 | .nav a { 277 | color: #000; 278 | text-decoration: none; 279 | } 280 | .nav a:hover { 281 | color: #000; 282 | font-weight: 500; 283 | text-decoration: none; 284 | } 285 | 286 | .b-dics__slider { 287 | color: #f0f0f0; 288 | } 289 | .b-dics__slider:after { 290 | width: 2px; 291 | } 292 | 293 | /* Go from zero to full opacity */ 294 | @keyframes fadeEffect { 295 | from {opacity: 0;} 296 | to {opacity: 1;} 297 | } -------------------------------------------------------------------------------- /web/static/images/logo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/static/images/logo.png -------------------------------------------------------------------------------- /web/static/images/logo.webp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/static/images/logo.webp -------------------------------------------------------------------------------- /web/static/js/app.js: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/static/js/app.js -------------------------------------------------------------------------------- /web/static/js/bulma-slider.js: -------------------------------------------------------------------------------- 1 | (function webpackUniversalModuleDefinition(root, factory) { 2 | if(typeof exports === 'object' && typeof module === 'object') 3 | module.exports = factory(); 4 | else if(typeof define === 'function' && define.amd) 5 | define([], factory); 6 | else if(typeof exports === 'object') 7 | exports["bulmaSlider"] = factory(); 8 | else 9 | root["bulmaSlider"] = factory(); 10 | })(typeof self !== 'undefined' ? self : this, function() { 11 | return /******/ (function(modules) { // webpackBootstrap 12 | /******/ // The module cache 13 | /******/ var installedModules = {}; 14 | /******/ 15 | /******/ // The require function 16 | /******/ function __webpack_require__(moduleId) { 17 | /******/ 18 | /******/ // Check if module is in cache 19 | /******/ if(installedModules[moduleId]) { 20 | /******/ return installedModules[moduleId].exports; 21 | /******/ } 22 | /******/ // Create a new module (and put it into the cache) 23 | /******/ var module = installedModules[moduleId] = { 24 | /******/ i: moduleId, 25 | /******/ l: false, 26 | /******/ exports: {} 27 | /******/ }; 28 | /******/ 29 | /******/ // Execute the module function 30 | /******/ modules[moduleId].call(module.exports, module, module.exports, __webpack_require__); 31 | /******/ 32 | /******/ // Flag the module as loaded 33 | /******/ module.l = true; 34 | /******/ 35 | /******/ // Return the exports of the module 36 | /******/ return module.exports; 37 | /******/ } 38 | /******/ 39 | /******/ 40 | /******/ // expose the modules object (__webpack_modules__) 41 | /******/ __webpack_require__.m = modules; 42 | /******/ 43 | /******/ // expose the module cache 44 | /******/ __webpack_require__.c = installedModules; 45 | /******/ 46 | /******/ // define getter function for harmony exports 47 | /******/ __webpack_require__.d = function(exports, name, getter) { 48 | /******/ if(!__webpack_require__.o(exports, name)) { 49 | /******/ Object.defineProperty(exports, name, { 50 | /******/ configurable: false, 51 | /******/ enumerable: true, 52 | /******/ get: getter 53 | /******/ }); 54 | /******/ } 55 | /******/ }; 56 | /******/ 57 | /******/ // getDefaultExport function for compatibility with non-harmony modules 58 | /******/ __webpack_require__.n = function(module) { 59 | /******/ var getter = module && module.__esModule ? 60 | /******/ function getDefault() { return module['default']; } : 61 | /******/ function getModuleExports() { return module; }; 62 | /******/ __webpack_require__.d(getter, 'a', getter); 63 | /******/ return getter; 64 | /******/ }; 65 | /******/ 66 | /******/ // Object.prototype.hasOwnProperty.call 67 | /******/ __webpack_require__.o = function(object, property) { return Object.prototype.hasOwnProperty.call(object, property); }; 68 | /******/ 69 | /******/ // __webpack_public_path__ 70 | /******/ __webpack_require__.p = ""; 71 | /******/ 72 | /******/ // Load entry module and return exports 73 | /******/ return __webpack_require__(__webpack_require__.s = 0); 74 | /******/ }) 75 | /************************************************************************/ 76 | /******/ ([ 77 | /* 0 */ 78 | /***/ (function(module, __webpack_exports__, __webpack_require__) { 79 | 80 | "use strict"; 81 | Object.defineProperty(__webpack_exports__, "__esModule", { value: true }); 82 | /* harmony export (binding) */ __webpack_require__.d(__webpack_exports__, "isString", function() { return isString; }); 83 | /* harmony import */ var __WEBPACK_IMPORTED_MODULE_0__events__ = __webpack_require__(1); 84 | var _extends = Object.assign || function (target) { for (var i = 1; i < arguments.length; i++) { var source = arguments[i]; for (var key in source) { if (Object.prototype.hasOwnProperty.call(source, key)) { target[key] = source[key]; } } } return target; }; 85 | 86 | var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }(); 87 | 88 | var _typeof = typeof Symbol === "function" && typeof Symbol.iterator === "symbol" ? function (obj) { return typeof obj; } : function (obj) { return obj && typeof Symbol === "function" && obj.constructor === Symbol && obj !== Symbol.prototype ? "symbol" : typeof obj; }; 89 | 90 | function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } } 91 | 92 | function _possibleConstructorReturn(self, call) { if (!self) { throw new ReferenceError("this hasn't been initialised - super() hasn't been called"); } return call && (typeof call === "object" || typeof call === "function") ? call : self; } 93 | 94 | function _inherits(subClass, superClass) { if (typeof superClass !== "function" && superClass !== null) { throw new TypeError("Super expression must either be null or a function, not " + typeof superClass); } subClass.prototype = Object.create(superClass && superClass.prototype, { constructor: { value: subClass, enumerable: false, writable: true, configurable: true } }); if (superClass) Object.setPrototypeOf ? Object.setPrototypeOf(subClass, superClass) : subClass.__proto__ = superClass; } 95 | 96 | 97 | 98 | var isString = function isString(unknown) { 99 | return typeof unknown === 'string' || !!unknown && (typeof unknown === 'undefined' ? 'undefined' : _typeof(unknown)) === 'object' && Object.prototype.toString.call(unknown) === '[object String]'; 100 | }; 101 | 102 | var bulmaSlider = function (_EventEmitter) { 103 | _inherits(bulmaSlider, _EventEmitter); 104 | 105 | function bulmaSlider(selector) { 106 | var options = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {}; 107 | 108 | _classCallCheck(this, bulmaSlider); 109 | 110 | var _this = _possibleConstructorReturn(this, (bulmaSlider.__proto__ || Object.getPrototypeOf(bulmaSlider)).call(this)); 111 | 112 | _this.element = typeof selector === 'string' ? document.querySelector(selector) : selector; 113 | // An invalid selector or non-DOM node has been provided. 114 | if (!_this.element) { 115 | throw new Error('An invalid selector or non-DOM node has been provided.'); 116 | } 117 | 118 | _this._clickEvents = ['click']; 119 | /// Set default options and merge with instance defined 120 | _this.options = _extends({}, options); 121 | 122 | _this.onSliderInput = _this.onSliderInput.bind(_this); 123 | 124 | _this.init(); 125 | return _this; 126 | } 127 | 128 | /** 129 | * Initiate all DOM element containing selector 130 | * @method 131 | * @return {Array} Array of all slider instances 132 | */ 133 | 134 | 135 | _createClass(bulmaSlider, [{ 136 | key: 'init', 137 | 138 | 139 | /** 140 | * Initiate plugin 141 | * @method init 142 | * @return {void} 143 | */ 144 | value: function init() { 145 | this._id = 'bulmaSlider' + new Date().getTime() + Math.floor(Math.random() * Math.floor(9999)); 146 | this.output = this._findOutputForSlider(); 147 | 148 | this._bindEvents(); 149 | 150 | if (this.output) { 151 | if (this.element.classList.contains('has-output-tooltip')) { 152 | // Get new output position 153 | var newPosition = this._getSliderOutputPosition(); 154 | 155 | // Set output position 156 | this.output.style['left'] = newPosition.position; 157 | } 158 | } 159 | 160 | this.emit('bulmaslider:ready', this.element.value); 161 | } 162 | }, { 163 | key: '_findOutputForSlider', 164 | value: function _findOutputForSlider() { 165 | var _this2 = this; 166 | 167 | var result = null; 168 | var outputs = document.getElementsByTagName('output') || []; 169 | 170 | Array.from(outputs).forEach(function (output) { 171 | if (output.htmlFor == _this2.element.getAttribute('id')) { 172 | result = output; 173 | return true; 174 | } 175 | }); 176 | return result; 177 | } 178 | }, { 179 | key: '_getSliderOutputPosition', 180 | value: function _getSliderOutputPosition() { 181 | // Update output position 182 | var newPlace, minValue; 183 | 184 | var style = window.getComputedStyle(this.element, null); 185 | // Measure width of range input 186 | var sliderWidth = parseInt(style.getPropertyValue('width'), 10); 187 | 188 | // Figure out placement percentage between left and right of input 189 | if (!this.element.getAttribute('min')) { 190 | minValue = 0; 191 | } else { 192 | minValue = this.element.getAttribute('min'); 193 | } 194 | var newPoint = (this.element.value - minValue) / (this.element.getAttribute('max') - minValue); 195 | 196 | // Prevent bubble from going beyond left or right (unsupported browsers) 197 | if (newPoint < 0) { 198 | newPlace = 0; 199 | } else if (newPoint > 1) { 200 | newPlace = sliderWidth; 201 | } else { 202 | newPlace = sliderWidth * newPoint; 203 | } 204 | 205 | return { 206 | 'position': newPlace + 'px' 207 | }; 208 | } 209 | 210 | /** 211 | * Bind all events 212 | * @method _bindEvents 213 | * @return {void} 214 | */ 215 | 216 | }, { 217 | key: '_bindEvents', 218 | value: function _bindEvents() { 219 | if (this.output) { 220 | // Add event listener to update output when slider value change 221 | this.element.addEventListener('input', this.onSliderInput, false); 222 | } 223 | } 224 | }, { 225 | key: 'onSliderInput', 226 | value: function onSliderInput(e) { 227 | e.preventDefault(); 228 | 229 | if (this.element.classList.contains('has-output-tooltip')) { 230 | // Get new output position 231 | var newPosition = this._getSliderOutputPosition(); 232 | 233 | // Set output position 234 | this.output.style['left'] = newPosition.position; 235 | } 236 | 237 | // Check for prefix and postfix 238 | var prefix = this.output.hasAttribute('data-prefix') ? this.output.getAttribute('data-prefix') : ''; 239 | var postfix = this.output.hasAttribute('data-postfix') ? this.output.getAttribute('data-postfix') : ''; 240 | 241 | // Update output with slider value 242 | this.output.value = prefix + this.element.value + postfix; 243 | 244 | this.emit('bulmaslider:ready', this.element.value); 245 | } 246 | }], [{ 247 | key: 'attach', 248 | value: function attach() { 249 | var _this3 = this; 250 | 251 | var selector = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : 'input[type="range"].slider'; 252 | var options = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : {}; 253 | 254 | var instances = new Array(); 255 | 256 | var elements = isString(selector) ? document.querySelectorAll(selector) : Array.isArray(selector) ? selector : [selector]; 257 | elements.forEach(function (element) { 258 | if (typeof element[_this3.constructor.name] === 'undefined') { 259 | var instance = new bulmaSlider(element, options); 260 | element[_this3.constructor.name] = instance; 261 | instances.push(instance); 262 | } else { 263 | instances.push(element[_this3.constructor.name]); 264 | } 265 | }); 266 | 267 | return instances; 268 | } 269 | }]); 270 | 271 | return bulmaSlider; 272 | }(__WEBPACK_IMPORTED_MODULE_0__events__["a" /* default */]); 273 | 274 | /* harmony default export */ __webpack_exports__["default"] = (bulmaSlider); 275 | 276 | /***/ }), 277 | /* 1 */ 278 | /***/ (function(module, __webpack_exports__, __webpack_require__) { 279 | 280 | "use strict"; 281 | var _createClass = function () { function defineProperties(target, props) { for (var i = 0; i < props.length; i++) { var descriptor = props[i]; descriptor.enumerable = descriptor.enumerable || false; descriptor.configurable = true; if ("value" in descriptor) descriptor.writable = true; Object.defineProperty(target, descriptor.key, descriptor); } } return function (Constructor, protoProps, staticProps) { if (protoProps) defineProperties(Constructor.prototype, protoProps); if (staticProps) defineProperties(Constructor, staticProps); return Constructor; }; }(); 282 | 283 | function _classCallCheck(instance, Constructor) { if (!(instance instanceof Constructor)) { throw new TypeError("Cannot call a class as a function"); } } 284 | 285 | var EventEmitter = function () { 286 | function EventEmitter() { 287 | var listeners = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : []; 288 | 289 | _classCallCheck(this, EventEmitter); 290 | 291 | this._listeners = new Map(listeners); 292 | this._middlewares = new Map(); 293 | } 294 | 295 | _createClass(EventEmitter, [{ 296 | key: "listenerCount", 297 | value: function listenerCount(eventName) { 298 | if (!this._listeners.has(eventName)) { 299 | return 0; 300 | } 301 | 302 | var eventListeners = this._listeners.get(eventName); 303 | return eventListeners.length; 304 | } 305 | }, { 306 | key: "removeListeners", 307 | value: function removeListeners() { 308 | var _this = this; 309 | 310 | var eventName = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : null; 311 | var middleware = arguments.length > 1 && arguments[1] !== undefined ? arguments[1] : false; 312 | 313 | if (eventName !== null) { 314 | if (Array.isArray(eventName)) { 315 | name.forEach(function (e) { 316 | return _this.removeListeners(e, middleware); 317 | }); 318 | } else { 319 | this._listeners.delete(eventName); 320 | 321 | if (middleware) { 322 | this.removeMiddleware(eventName); 323 | } 324 | } 325 | } else { 326 | this._listeners = new Map(); 327 | } 328 | } 329 | }, { 330 | key: "middleware", 331 | value: function middleware(eventName, fn) { 332 | var _this2 = this; 333 | 334 | if (Array.isArray(eventName)) { 335 | name.forEach(function (e) { 336 | return _this2.middleware(e, fn); 337 | }); 338 | } else { 339 | if (!Array.isArray(this._middlewares.get(eventName))) { 340 | this._middlewares.set(eventName, []); 341 | } 342 | 343 | this._middlewares.get(eventName).push(fn); 344 | } 345 | } 346 | }, { 347 | key: "removeMiddleware", 348 | value: function removeMiddleware() { 349 | var _this3 = this; 350 | 351 | var eventName = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : null; 352 | 353 | if (eventName !== null) { 354 | if (Array.isArray(eventName)) { 355 | name.forEach(function (e) { 356 | return _this3.removeMiddleware(e); 357 | }); 358 | } else { 359 | this._middlewares.delete(eventName); 360 | } 361 | } else { 362 | this._middlewares = new Map(); 363 | } 364 | } 365 | }, { 366 | key: "on", 367 | value: function on(name, callback) { 368 | var _this4 = this; 369 | 370 | var once = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : false; 371 | 372 | if (Array.isArray(name)) { 373 | name.forEach(function (e) { 374 | return _this4.on(e, callback); 375 | }); 376 | } else { 377 | name = name.toString(); 378 | var split = name.split(/,|, | /); 379 | 380 | if (split.length > 1) { 381 | split.forEach(function (e) { 382 | return _this4.on(e, callback); 383 | }); 384 | } else { 385 | if (!Array.isArray(this._listeners.get(name))) { 386 | this._listeners.set(name, []); 387 | } 388 | 389 | this._listeners.get(name).push({ once: once, callback: callback }); 390 | } 391 | } 392 | } 393 | }, { 394 | key: "once", 395 | value: function once(name, callback) { 396 | this.on(name, callback, true); 397 | } 398 | }, { 399 | key: "emit", 400 | value: function emit(name, data) { 401 | var _this5 = this; 402 | 403 | var silent = arguments.length > 2 && arguments[2] !== undefined ? arguments[2] : false; 404 | 405 | name = name.toString(); 406 | var listeners = this._listeners.get(name); 407 | var middlewares = null; 408 | var doneCount = 0; 409 | var execute = silent; 410 | 411 | if (Array.isArray(listeners)) { 412 | listeners.forEach(function (listener, index) { 413 | // Start Middleware checks unless we're doing a silent emit 414 | if (!silent) { 415 | middlewares = _this5._middlewares.get(name); 416 | // Check and execute Middleware 417 | if (Array.isArray(middlewares)) { 418 | middlewares.forEach(function (middleware) { 419 | middleware(data, function () { 420 | var newData = arguments.length > 0 && arguments[0] !== undefined ? arguments[0] : null; 421 | 422 | if (newData !== null) { 423 | data = newData; 424 | } 425 | doneCount++; 426 | }, name); 427 | }); 428 | 429 | if (doneCount >= middlewares.length) { 430 | execute = true; 431 | } 432 | } else { 433 | execute = true; 434 | } 435 | } 436 | 437 | // If Middleware checks have been passed, execute 438 | if (execute) { 439 | if (listener.once) { 440 | listeners[index] = null; 441 | } 442 | listener.callback(data); 443 | } 444 | }); 445 | 446 | // Dirty way of removing used Events 447 | while (listeners.indexOf(null) !== -1) { 448 | listeners.splice(listeners.indexOf(null), 1); 449 | } 450 | } 451 | } 452 | }]); 453 | 454 | return EventEmitter; 455 | }(); 456 | 457 | /* harmony default export */ __webpack_exports__["a"] = (EventEmitter); 458 | 459 | /***/ }) 460 | /******/ ])["default"]; 461 | }); -------------------------------------------------------------------------------- /web/static/js/bulma-slider.min.js: -------------------------------------------------------------------------------- 1 | !function(t,e){"object"==typeof exports&&"object"==typeof module?module.exports=e():"function"==typeof define&&define.amd?define([],e):"object"==typeof exports?exports.bulmaSlider=e():t.bulmaSlider=e()}("undefined"!=typeof self?self:this,function(){return function(n){var r={};function i(t){if(r[t])return r[t].exports;var e=r[t]={i:t,l:!1,exports:{}};return n[t].call(e.exports,e,e.exports,i),e.l=!0,e.exports}return i.m=n,i.c=r,i.d=function(t,e,n){i.o(t,e)||Object.defineProperty(t,e,{configurable:!1,enumerable:!0,get:n})},i.n=function(t){var e=t&&t.__esModule?function(){return t.default}:function(){return t};return i.d(e,"a",e),e},i.o=function(t,e){return Object.prototype.hasOwnProperty.call(t,e)},i.p="",i(i.s=0)}([function(t,e,n){"use strict";Object.defineProperty(e,"__esModule",{value:!0}),n.d(e,"isString",function(){return l});var r=n(1),i=Object.assign||function(t){for(var e=1;e=l.length&&(s=!0)):s=!0),s&&(t.once&&(u[e]=null),t.callback(r))});-1!==u.indexOf(null);)u.splice(u.indexOf(null),1)}}]),e}();e.a=i}]).default}); -------------------------------------------------------------------------------- /web/static/js/dics.original.js: -------------------------------------------------------------------------------- 1 | /* 2 | * Dics: Definitive image comparison slider. A multiple image vanilla comparison slider. 3 | * 4 | * By Abel Cabeza Román, a Codictados developer 5 | * Src: https://github.com/abelcabezaroman/definitive-image-comparison-slider 6 | * Example: http://codictados.com/portfolio/definitive-image-comparison-slider-demo/ 7 | */ 8 | 9 | /** 10 | * 11 | */ 12 | 13 | /** 14 | * 15 | * @type {{container: null, filters: null, hideTexts: null, textPosition: string, linesOrientation: string, rotate: number, arrayBackgroundColorText: null, arrayColorText: null, linesColor: null}} 16 | */ 17 | let defaultOptions = { 18 | container: null, // **REQUIRED**: HTML container | `document.querySelector('.b-dics')` | 19 | filters: null, // Array of CSS string filters |`['blur(3px)', 'grayscale(1)', 'sepia(1)', 'saturate(3)']` | 20 | hideTexts: true, // Show text only when you hover the image container |`true`,`false`| 21 | textPosition: "center", // Set the prefer text position |`'center'`,`'top'`, `'right'`, `'bottom'`, `'left'` | 22 | linesOrientation: "horizontal", // Change the orientation of lines |`'horizontal'`,`'vertical'` | 23 | rotate: 0, // Rotate the image container (not too useful but it's a beatiful effect. String of rotate CSS rule) |`'45deg'`| 24 | arrayBackgroundColorText: null, // Change the bacground-color of sections texts with an array |`['#000000', '#FFFFFF']`| 25 | arrayColorText: null, // Change the color of texts with an array |`['#FFFFFF', '#000000']`| 26 | linesColor: null // Change the lines and arrows color |`'rgb(0,0,0)'`| 27 | 28 | }; 29 | 30 | /** 31 | * 32 | * @param options 33 | * @constructor 34 | */ 35 | let Dics = function(options) { 36 | this.options = utils.extend({}, [defaultOptions, options], { 37 | clearEmpty: true 38 | }); 39 | 40 | this.container = this.options.container; 41 | 42 | if (this.container == null) { 43 | console.error("Container element not found!"); 44 | } else { 45 | 46 | this._setOrientation(this.options.linesOrientation, this.container); 47 | this.images = this._getImages(); 48 | this.sliders = []; 49 | this._activeSlider = null; 50 | 51 | 52 | this._load(this.images[0]); 53 | 54 | } 55 | }; 56 | 57 | 58 | /** 59 | * 60 | * @private 61 | */ 62 | Dics.prototype._load = function(firstImage, maxCounter = 100000) { 63 | if (firstImage.naturalWidth) { 64 | this._buidAfterFirstImageLoad(firstImage); 65 | window.addEventListener("resize", () => { 66 | this._setContainerWidth(firstImage); 67 | this._resetSizes(); 68 | }); 69 | 70 | } else { 71 | if (maxCounter > 0) { 72 | maxCounter--; 73 | setTimeout(() => { 74 | this._load(firstImage, maxCounter); 75 | }, 100); 76 | } else { 77 | console.error("error loading images"); 78 | } 79 | 80 | } 81 | }; 82 | 83 | 84 | /** 85 | * 86 | * @private 87 | */ 88 | Dics.prototype._buidAfterFirstImageLoad = function(firstImage) { 89 | this._setContainerWidth(firstImage); 90 | 91 | this._build(); 92 | this._setEvents(); 93 | }; 94 | 95 | 96 | /** 97 | * 98 | * @private 99 | */ 100 | Dics.prototype._setContainerWidth = function(firstImage) { 101 | this.options.container.style.height = `${this._calcContainerHeight(firstImage)}px`; 102 | }; 103 | 104 | 105 | /** 106 | * 107 | * @private 108 | */ 109 | Dics.prototype._setOpacityContainerForLoading = function(opacity) { 110 | this.options.container.style.opacity = opacity; 111 | }; 112 | 113 | 114 | /** 115 | * Reset sizes on window size change 116 | * @private 117 | */ 118 | Dics.prototype._resetSizes = function() { 119 | let dics = this; 120 | let imagesLength = dics.images.length; 121 | 122 | let initialImagesContainerWidth = dics.container.getBoundingClientRect()[dics.config.sizeField] / imagesLength; 123 | 124 | const sections$$ = dics.container.querySelectorAll("[data-function='b-dics__section']"); 125 | for (let i = 0; i < sections$$.length; i++) { 126 | let section$$ = sections$$[i]; 127 | 128 | section$$.style.flex = `0 0 ${initialImagesContainerWidth}px`; 129 | 130 | section$$.querySelector(".b-dics__image").style[this.config.positionField] = `${i * -initialImagesContainerWidth}px`; 131 | 132 | const slider$$ = section$$.querySelector(".b-dics__slider"); 133 | if (slider$$) { 134 | slider$$.style[this.config.positionField] = `${initialImagesContainerWidth * (i + 1)}px`; 135 | 136 | } 137 | 138 | } 139 | 140 | }; 141 | 142 | /** 143 | * Build HTML 144 | * @private 145 | */ 146 | Dics.prototype._build = function() { 147 | let dics = this; 148 | 149 | dics._applyGlobalClass(dics.options); 150 | 151 | let imagesLength = dics.images.length; 152 | 153 | 154 | let initialImagesContainerWidth = dics.container.getBoundingClientRect()[dics.config.sizeField] / imagesLength; 155 | 156 | for (let i = 0; i < imagesLength; i++) { 157 | let image = dics.images[i]; 158 | let section = dics._createElement("div", "b-dics__section"); 159 | let imageContainer = dics._createElement("div", "b-dics__image-container"); 160 | let slider = dics._createSlider(i, initialImagesContainerWidth); 161 | 162 | dics._createAltText(image, i, imageContainer); 163 | 164 | dics._applyFilter(image, i, dics.options.filters); 165 | dics._rotate(image, imageContainer); 166 | 167 | 168 | section.setAttribute("data-function", "b-dics__section"); 169 | section.style.flex = `0 0 ${initialImagesContainerWidth}px`; 170 | 171 | image.classList.add("b-dics__image"); 172 | 173 | section.appendChild(imageContainer); 174 | imageContainer.appendChild(image); 175 | 176 | if (i < imagesLength - 1) { 177 | section.appendChild(slider); 178 | } 179 | 180 | dics.container.appendChild(section); 181 | 182 | image.style[this.config.positionField] = `${i * -initialImagesContainerWidth}px`; 183 | 184 | 185 | } 186 | 187 | this.sections = this._getSections(); 188 | this._setOpacityContainerForLoading(1); 189 | }; 190 | 191 | 192 | /** 193 | * 194 | * @returns {NodeListOf | NodeListOf | NodeListOf} 195 | * @private 196 | */ 197 | Dics.prototype._getImages = function() { 198 | return this.container.querySelectorAll("img"); 199 | }; 200 | 201 | 202 | /** 203 | * 204 | * @returns {NodeListOf | NodeListOf | NodeListOf} 205 | * @private 206 | */ 207 | Dics.prototype._getSections = function() { 208 | return this.container.querySelectorAll("[data-function=\"b-dics__section\"]"); 209 | }; 210 | 211 | /** 212 | * 213 | * @param elementClass 214 | * @param className 215 | * @returns {HTMLElement | HTMLSelectElement | HTMLLegendElement | HTMLTableCaptionElement | HTMLTextAreaElement | HTMLModElement | HTMLHRElement | HTMLOutputElement | HTMLPreElement | HTMLEmbedElement | HTMLCanvasElement | HTMLFrameSetElement | HTMLMarqueeElement | HTMLScriptElement | HTMLInputElement | HTMLUnknownElement | HTMLMetaElement | HTMLStyleElement | HTMLObjectElement | HTMLTemplateElement | HTMLBRElement | HTMLAudioElement | HTMLIFrameElement | HTMLMapElement | HTMLTableElement | HTMLAnchorElement | HTMLMenuElement | HTMLPictureElement | HTMLParagraphElement | HTMLTableDataCellElement | HTMLTableSectionElement | HTMLQuoteElement | HTMLTableHeaderCellElement | HTMLProgressElement | HTMLLIElement | HTMLTableRowElement | HTMLFontElement | HTMLSpanElement | HTMLTableColElement | HTMLOptGroupElement | HTMLDataElement | HTMLDListElement | HTMLFieldSetElement | HTMLSourceElement | HTMLBodyElement | HTMLDirectoryElement | HTMLDivElement | HTMLUListElement | HTMLHtmlElement | HTMLAreaElement | HTMLMeterElement | HTMLAppletElement | HTMLFrameElement | HTMLOptionElement | HTMLImageElement | HTMLLinkElement | HTMLHeadingElement | HTMLSlotElement | HTMLVideoElement | HTMLBaseFontElement | HTMLTitleElement | HTMLButtonElement | HTMLHeadElement | HTMLParamElement | HTMLTrackElement | HTMLOListElement | HTMLDataListElement | HTMLLabelElement | HTMLFormElement | HTMLTimeElement | HTMLBaseElement} 216 | * @private 217 | */ 218 | Dics.prototype._createElement = function(elementClass, className) { 219 | let newElement = document.createElement(elementClass); 220 | 221 | newElement.classList.add(className); 222 | 223 | return newElement; 224 | }; 225 | 226 | /** 227 | * Set need DOM events 228 | * @private 229 | */ 230 | Dics.prototype._setEvents = function() { 231 | let dics = this; 232 | 233 | dics._disableImageDrag(); 234 | 235 | dics._isGoingRight = null; 236 | 237 | let oldx = 0; 238 | 239 | let listener = function(event) { 240 | 241 | let xPageCoord = event.pageX ? event.pageX : event.touches[0].pageX; 242 | 243 | if (xPageCoord < oldx) { 244 | dics._isGoingRight = false; 245 | } else if (xPageCoord > oldx) { 246 | dics._isGoingRight = true; 247 | } 248 | 249 | oldx = xPageCoord; 250 | 251 | let position = dics._calcPosition(event); 252 | 253 | let beforeSectionsWidth = dics._beforeSectionsWidth(dics.sections, dics.images, dics._activeSlider); 254 | 255 | let calcMovePixels = position - beforeSectionsWidth; 256 | 257 | dics.sliders[dics._activeSlider].style[dics.config.positionField] = `${position}px`; 258 | 259 | dics._pushSections(calcMovePixels, position); 260 | }; 261 | 262 | dics.container.addEventListener("click", listener); 263 | 264 | for (let i = 0; i < dics.sliders.length; i++) { 265 | let slider = dics.sliders[i]; 266 | utils.setMultiEvents(slider, ["mousedown", "touchstart"], function(event) { 267 | dics._activeSlider = i; 268 | 269 | dics._clickPosition = dics._calcPosition(event); 270 | 271 | slider.classList.add("b-dics__slider--active"); 272 | 273 | utils.setMultiEvents(dics.container, ["mousemove", "touchmove"], listener); 274 | }); 275 | } 276 | 277 | 278 | let listener2 = function() { 279 | let activeElements = dics.container.querySelectorAll(".b-dics__slider--active"); 280 | 281 | for (let activeElement of activeElements) { 282 | activeElement.classList.remove("b-dics__slider--active"); 283 | utils.removeMultiEvents(dics.container, ["mousemove", "touchmove"], listener); 284 | } 285 | }; 286 | 287 | utils.setMultiEvents(document.body, ["mouseup", "touchend"], listener2); 288 | 289 | 290 | }; 291 | 292 | /** 293 | * 294 | * @param sections 295 | * @param images 296 | * @param activeSlider 297 | * @returns {number} 298 | * @private 299 | */ 300 | Dics.prototype._beforeSectionsWidth = function(sections, images, activeSlider) { 301 | let width = 0; 302 | for (let i = 0; i < sections.length; i++) { 303 | let section = sections[i]; 304 | if (i !== activeSlider) { 305 | width += section.getBoundingClientRect()[this.config.sizeField]; 306 | } else { 307 | return width; 308 | } 309 | } 310 | }; 311 | 312 | /** 313 | * 314 | * @returns {number} 315 | * @private 316 | */ 317 | Dics.prototype._calcContainerHeight = function(firstImage) { 318 | let imgHeight = firstImage.naturalHeight; 319 | let imgWidth = firstImage.naturalWidth; 320 | let containerWidth = this.options.container.getBoundingClientRect().width; 321 | 322 | return (containerWidth / imgWidth) * imgHeight; 323 | }; 324 | 325 | 326 | /** 327 | * 328 | * @param sections 329 | * @param images 330 | * @private 331 | */ 332 | Dics.prototype._setLeftToImages = function(sections, images) { 333 | let size = 0; 334 | for (let i = 0; i < images.length; i++) { 335 | let image = images[i]; 336 | 337 | image.style[this.config.positionField] = `-${size}px`; 338 | size += sections[i].getBoundingClientRect()[this.config.sizeField]; 339 | 340 | this.sliders[i].style[this.config.positionField] = `${size}px`; 341 | 342 | } 343 | }; 344 | 345 | 346 | /** 347 | * 348 | * @private 349 | */ 350 | Dics.prototype._disableImageDrag = function() { 351 | for (let i = 0; i < this.images.length; i++) { 352 | this.sliders[i].addEventListener("dragstart", function(e) { 353 | e.preventDefault(); 354 | }); 355 | this.images[i].addEventListener("dragstart", function(e) { 356 | e.preventDefault(); 357 | }); 358 | } 359 | }; 360 | 361 | /** 362 | * 363 | * @param image 364 | * @param index 365 | * @param filters 366 | * @private 367 | */ 368 | Dics.prototype._applyFilter = function(image, index, filters) { 369 | if (filters) { 370 | image.style.filter = filters[index]; 371 | } 372 | }; 373 | 374 | /** 375 | * 376 | * @param options 377 | * @private 378 | */ 379 | Dics.prototype._applyGlobalClass = function(options) { 380 | let container = options.container; 381 | 382 | 383 | if (options.hideTexts) { 384 | container.classList.add("b-dics--hide-texts"); 385 | } 386 | 387 | if (options.linesOrientation === "vertical") { 388 | container.classList.add("b-dics--vertical"); 389 | } 390 | 391 | if (options.textPosition === "center") { 392 | container.classList.add("b-dics--tp-center"); 393 | } else if (options.textPosition === "bottom") { 394 | container.classList.add("b-dics--tp-bottom"); 395 | } else if (options.textPosition === "left") { 396 | container.classList.add("b-dics--tp-left"); 397 | } else if (options.textPosition === "right") { 398 | container.classList.add("b-dics--tp-right"); 399 | } 400 | }; 401 | 402 | 403 | Dics.prototype._createSlider = function(i, initialImagesContainerWidth) { 404 | let slider = this._createElement("div", "b-dics__slider"); 405 | 406 | if (this.options.linesColor) { 407 | slider.style.color = this.options.linesColor; 408 | } 409 | 410 | slider.style[this.config.positionField] = `${initialImagesContainerWidth * (i + 1)}px`; 411 | 412 | this.sliders.push(slider); 413 | 414 | 415 | return slider; 416 | }; 417 | 418 | 419 | /** 420 | * 421 | * @param image 422 | * @param i 423 | * @param imageContainer 424 | * @private 425 | */ 426 | Dics.prototype._createAltText = function(image, i, imageContainer) { 427 | let textContent = image.getAttribute("alt"); 428 | if (textContent) { 429 | let text = this._createElement("p", "b-dics__text"); 430 | 431 | if (this.options.arrayBackgroundColorText) { 432 | text.style.backgroundColor = this.options.arrayBackgroundColorText[i]; 433 | } 434 | if (this.options.arrayColorText) { 435 | text.style.color = this.options.arrayColorText[i]; 436 | } 437 | 438 | text.appendChild(document.createTextNode(textContent)); 439 | 440 | imageContainer.appendChild(text); 441 | } 442 | }; 443 | 444 | 445 | /** 446 | * 447 | * @param image 448 | * @param imageContainer 449 | * @private 450 | */ 451 | Dics.prototype._rotate = function(image, imageContainer) { 452 | image.style.rotate = `-${this.options.rotate}`; 453 | imageContainer.style.rotate = this.options.rotate; 454 | 455 | }; 456 | 457 | 458 | /** 459 | * 460 | * @private 461 | */ 462 | Dics.prototype._removeActiveElements = function() { 463 | let activeElements = Dics.container.querySelectorAll(".b-dics__slider--active"); 464 | 465 | for (let activeElement of activeElements) { 466 | activeElement.classList.remove("b-dics__slider--active"); 467 | utils.removeMultiEvents(Dics.container, ["mousemove", "touchmove"], Dics.prototype._removeActiveElements); 468 | } 469 | }; 470 | 471 | 472 | /** 473 | * 474 | * @param linesOrientation 475 | * @private 476 | */ 477 | Dics.prototype._setOrientation = function(linesOrientation) { 478 | this.config = {}; 479 | 480 | if (linesOrientation === "vertical") { 481 | this.config.offsetSizeField = "offsetHeight"; 482 | this.config.offsetPositionField = "offsetTop"; 483 | this.config.sizeField = "height"; 484 | this.config.positionField = "top"; 485 | this.config.clientField = "clientY"; 486 | this.config.pageField = "pageY"; 487 | } else { 488 | this.config.offsetSizeField = "offsetWidth"; 489 | this.config.offsetPositionField = "offsetLeft"; 490 | this.config.sizeField = "width"; 491 | this.config.positionField = "left"; 492 | this.config.clientField = "clientX"; 493 | this.config.pageField = "pageX"; 494 | } 495 | 496 | 497 | }; 498 | 499 | 500 | /** 501 | * 502 | * @param event 503 | * @returns {number} 504 | * @private 505 | */ 506 | Dics.prototype._calcPosition = function(event) { 507 | let containerCoords = this.container.getBoundingClientRect(); 508 | let pixel = !isNaN(event[this.config.clientField]) ? event[this.config.clientField] : event.touches[0][this.config.clientField]; 509 | 510 | return containerCoords[this.config.positionField] < pixel ? pixel - containerCoords[this.config.positionField] : 0; 511 | }; 512 | 513 | 514 | /** 515 | * 516 | * @private 517 | */ 518 | Dics.prototype._pushSections = function(calcMovePixels, position) { 519 | // if (this._rePosUnderActualSections(position)) { 520 | this._setFlex(position, this._isGoingRight); 521 | 522 | let section = this.sections[this._activeSlider]; 523 | let postActualSection = this.sections[this._activeSlider + 1]; 524 | let sectionWidth = postActualSection.getBoundingClientRect()[this.config.sizeField] - (calcMovePixels - this.sections[this._activeSlider].getBoundingClientRect()[this.config.sizeField]); 525 | 526 | 527 | section.style.flex = this._isGoingRight === true ? `2 0 ${calcMovePixels}px` : `1 1 ${calcMovePixels}px`; 528 | postActualSection.style.flex = this._isGoingRight === true ? ` ${sectionWidth}px` : `2 0 ${sectionWidth}px`; 529 | 530 | this._setLeftToImages(this.sections, this.images); 531 | 532 | // } 533 | }; 534 | 535 | 536 | /** 537 | * 538 | * @private 539 | */ 540 | Dics.prototype._setFlex = function(position, isGoingRight) { 541 | let beforeSumSectionsSize = 0; 542 | 543 | 544 | for (let i = 0; i < this.sections.length; i++) { 545 | let section = this.sections[i]; 546 | const sectionSize = section.getBoundingClientRect()[this.config.sizeField]; 547 | 548 | beforeSumSectionsSize += sectionSize; 549 | 550 | if ((isGoingRight && position > (beforeSumSectionsSize - sectionSize) && i > this._activeSlider) || (!isGoingRight && position < beforeSumSectionsSize) && i < this._activeSlider) { 551 | section.style.flex = `1 100 ${sectionSize}px`; 552 | } else { 553 | section.style.flex = `0 0 ${sectionSize}px`; 554 | } 555 | 556 | } 557 | }; 558 | 559 | 560 | /** 561 | * 562 | * @type {{extend: (function(*=, *, *): *), setMultiEvents: setMultiEvents, removeMultiEvents: removeMultiEvents, getConstructor: (function(*=): string)}} 563 | */ 564 | let utils = { 565 | 566 | 567 | /** 568 | * Native extend object 569 | * @param target 570 | * @param objects 571 | * @param options 572 | * @returns {*} 573 | */ 574 | extend: function(target, objects, options) { 575 | 576 | for (let object in objects) { 577 | if (objects.hasOwnProperty(object)) { 578 | recursiveMerge(target, objects[object]); 579 | } 580 | } 581 | 582 | function recursiveMerge (target, object) { 583 | for (let property in object) { 584 | if (object.hasOwnProperty(property)) { 585 | let current = object[property]; 586 | if (utils.getConstructor(current) === "Object") { 587 | if (!target[property]) { 588 | target[property] = {}; 589 | } 590 | recursiveMerge(target[property], current); 591 | } else { 592 | // clearEmpty 593 | if (options.clearEmpty) { 594 | if (current == null) { 595 | continue; 596 | } 597 | } 598 | target[property] = current; 599 | } 600 | } 601 | } 602 | } 603 | 604 | return target; 605 | }, 606 | 607 | 608 | /** 609 | * Set Multi addEventListener 610 | * @param element 611 | * @param events 612 | * @param func 613 | */ 614 | setMultiEvents: function(element, events, func) { 615 | for (let i = 0; i < events.length; i++) { 616 | element.addEventListener(events[i], func); 617 | } 618 | }, 619 | 620 | 621 | /** 622 | * 623 | * @param element 624 | * @param events 625 | * @param func 626 | */ 627 | removeMultiEvents: function(element, events, func) { 628 | for (let i = 0; i < events.length; i++) { 629 | element.removeEventListener(events[i], func, false); 630 | } 631 | }, 632 | 633 | 634 | /** 635 | * Get object constructor 636 | * @param object 637 | * @returns {string} 638 | */ 639 | getConstructor: function(object) { 640 | return Object.prototype.toString.call(object).slice(8, -1); 641 | } 642 | }; 643 | 644 | -------------------------------------------------------------------------------- /web/static/js/event_handler.js: -------------------------------------------------------------------------------- 1 | document.addEventListener('DOMContentLoaded', domReady); 2 | 3 | function domReady() { 4 | new Dics({ 5 | container: document.querySelectorAll('.b-dics')[0], 6 | hideTexts: false, 7 | textPosition: "bottom" 8 | 9 | }); 10 | new Dics({ 11 | container: document.querySelectorAll('.b-dics')[1], 12 | hideTexts: false, 13 | textPosition: "bottom" 14 | 15 | }); 16 | } 17 | 18 | function largeSceneEvent(idx) { 19 | let dics = document.querySelectorAll('.b-dics')[0] 20 | let sections = dics.getElementsByClassName('b-dics__section') 21 | let imagesLength = 3 22 | for (let i = 0; i < imagesLength; i++) { 23 | let image = sections[i].getElementsByClassName('b-dics__image-container')[0].getElementsByClassName('b-dics__image')[0] 24 | switch (idx) { 25 | case 0: 26 | image.src = 'assets/img/nvidia/'; 27 | break; 28 | case 1: 29 | image.src = 'assets/img/jhu/'; 30 | break; 31 | case 2: 32 | image.src = 'assets/img/Barn/'; 33 | break; 34 | case 3: 35 | image.src = 'assets/img/Caterpillar/'; 36 | break; 37 | case 4: 38 | image.src = 'assets/img/Courthouse/'; 39 | break; 40 | case 5: 41 | image.src = 'assets/img/Ignatius/'; 42 | break; 43 | case 6: 44 | image.src = 'assets/img/Meetingroom/'; 45 | break; 46 | case 7: 47 | image.src = 'assets/img/Truck/'; 48 | break; 49 | } 50 | switch (i) { 51 | case 0: 52 | image.src = image.src + '/rgb.png'; 53 | break; 54 | case 1: 55 | image.src = image.src + '/mesh.png'; 56 | break; 57 | case 2: 58 | image.src = image.src + '/normal.png'; 59 | break; 60 | } 61 | } 62 | 63 | scene_list = document.getElementById("large-scale-recon-1").children; 64 | for (let i = 0; i < scene_list.length; i++) { 65 | if (idx == i) { 66 | scene_list[i].children[0].className = "nav-link active" 67 | } 68 | else { 69 | scene_list[i].children[0].className = "nav-link" 70 | } 71 | } 72 | scene_list = document.getElementById("large-scale-recon-2").children; 73 | for (let i = 0; i < scene_list.length; i++) { 74 | if (idx == i+2) { 75 | scene_list[i].children[0].className = "nav-link active" 76 | } 77 | else { 78 | scene_list[i].children[0].className = "nav-link" 79 | } 80 | } 81 | } 82 | 83 | function objectSceneEvent(idx) { 84 | let dics = document.querySelectorAll('.b-dics')[0] 85 | let sections = dics.getElementsByClassName('b-dics__section') 86 | let imagesLength = 4 87 | for (let i = 0; i < imagesLength; i++) { 88 | let image = sections[i].getElementsByClassName('b-dics__image-container')[0].getElementsByClassName('b-dics__image')[0] 89 | switch (idx) { 90 | case 0: 91 | image.src = 'resources/self/half_bahnhof'; 92 | break; 93 | case 1: 94 | image.src = 'resources/self/yard_high'; 95 | break; 96 | case 2: 97 | image.src = 'resources/self/adc'; 98 | break; 99 | case 3: 100 | image.src = 'resources/self/drone'; 101 | break; 102 | case 4: 103 | image.src = 'resources/self/polybahn'; 104 | break; 105 | case 5: 106 | image.src = 'resources/self/rigi'; 107 | break; 108 | case 6: 109 | image.src = 'resources/self/dlab_high'; 110 | break; 111 | case 7: 112 | image.src = 'resources/self/dlab_spot'; 113 | break; 114 | } 115 | switch (i) { 116 | case 0: 117 | image.src = image.src + '/nerfw.png'; 118 | break; 119 | case 1: 120 | image.src = image.src + '/robust.png'; 121 | break; 122 | case 2: 123 | image.src = image.src + '/ours.png'; 124 | break; 125 | case 3: 126 | image.src = image.src + '/gt.png'; 127 | break; 128 | 129 | } 130 | } 131 | 132 | let scene_list = document.getElementById("object-scale-recon").children; 133 | for (let i = 0; i < scene_list.length; i++) { 134 | if (idx == i) { 135 | scene_list[i].children[0].className = "nav-link active" 136 | } 137 | else { 138 | scene_list[i].children[0].className = "nav-link" 139 | } 140 | } 141 | } 142 | 143 | function ablation3DEvent(idx) { 144 | let dics = document.querySelectorAll('.b-dics')[1] 145 | let sections = dics.getElementsByClassName('b-dics__section') 146 | let imagesLength = 4 147 | for (let i = 0; i < imagesLength; i++) { 148 | let image = sections[i].getElementsByClassName('b-dics__image-container')[0].getElementsByClassName('b-dics__image')[0] 149 | switch (idx) { 150 | case 0: 151 | image.src = 'resources/360_stmt_ablation/bicycle_0'; 152 | break; 153 | case 1: 154 | image.src = 'resources/360_stmt_ablation/bicycle_3'; 155 | break; 156 | case 2: 157 | image.src = 'resources/360_stmt_ablation/bicycle_5'; 158 | break; 159 | case 3: 160 | image.src = 'resources/360_stmt_ablation/garden_0'; 161 | break; 162 | case 4: 163 | image.src = 'resources/360_stmt_ablation/garden_1'; 164 | break; 165 | case 5: 166 | image.src = 'resources/360_stmt_ablation/treehill_9'; 167 | break; 168 | } 169 | switch (i) { 170 | case 0: 171 | image.src = image.src + '_no3d.png'; 172 | break; 173 | case 1: 174 | image.src = image.src + '_ours.png'; 175 | break; 176 | case 2: 177 | image.src = image.src + '_upgt.png'; 178 | break; 179 | case 3: 180 | image.src = image.src + '_gt.png'; 181 | break; 182 | } 183 | } 184 | 185 | let scene_list = document.getElementById("ablation-3d-filter").children; 186 | for (let i = 0; i < scene_list.length; i++) { 187 | if (idx == i) { 188 | scene_list[i].children[0].className = "nav-link active" 189 | } 190 | else { 191 | scene_list[i].children[0].className = "nav-link" 192 | } 193 | } 194 | } -------------------------------------------------------------------------------- /web/static/js/index.js: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Yaepiii/C-LOAM/caba63a081b9cf5387d01324fcbcd5f1d2313129/web/static/js/index.js -------------------------------------------------------------------------------- /web/static/js/video_comparison.js: -------------------------------------------------------------------------------- 1 | // Written by Dor Verbin, October 2021 2 | // This is based on: http://thenewcode.com/364/Interactive-Before-and-After-Video-Comparison-in-HTML5-Canvas 3 | // With additional modifications based on: https://jsfiddle.net/7sk5k4gp/13/ 4 | 5 | function playVids(videoId) { 6 | var videoMerge = document.getElementById(videoId + "Merge"); 7 | var vid = document.getElementById(videoId); 8 | 9 | var position = 0.5; 10 | var vidWidth = vid.videoWidth/2; 11 | var vidHeight = vid.videoHeight; 12 | 13 | var mergeContext = videoMerge.getContext("2d"); 14 | 15 | 16 | if (vid.readyState > 3) { 17 | vid.play(); 18 | 19 | function trackLocation(e) { 20 | // Normalize to [0, 1] 21 | bcr = videoMerge.getBoundingClientRect(); 22 | position = ((e.pageX - bcr.x) / bcr.width); 23 | } 24 | function trackLocationTouch(e) { 25 | // Normalize to [0, 1] 26 | bcr = videoMerge.getBoundingClientRect(); 27 | position = ((e.touches[0].pageX - bcr.x) / bcr.width); 28 | } 29 | 30 | videoMerge.addEventListener("mousemove", trackLocation, false); 31 | videoMerge.addEventListener("touchstart", trackLocationTouch, false); 32 | videoMerge.addEventListener("touchmove", trackLocationTouch, false); 33 | 34 | 35 | function drawLoop() { 36 | mergeContext.drawImage(vid, 0, 0, vidWidth, vidHeight, 0, 0, vidWidth, vidHeight); 37 | var colStart = (vidWidth * position).clamp(0.0, vidWidth); 38 | var colWidth = (vidWidth - (vidWidth * position)).clamp(0.0, vidWidth); 39 | mergeContext.drawImage(vid, colStart+vidWidth, 0, colWidth, vidHeight, colStart, 0, colWidth, vidHeight); 40 | requestAnimationFrame(drawLoop); 41 | 42 | 43 | var arrowLength = 0.09 * vidHeight; 44 | var arrowheadWidth = 0.025 * vidHeight; 45 | var arrowheadLength = 0.04 * vidHeight; 46 | var arrowPosY = vidHeight / 10; 47 | var arrowWidth = 0.007 * vidHeight; 48 | var currX = vidWidth * position; 49 | 50 | // Draw circle 51 | mergeContext.arc(currX, arrowPosY, arrowLength*0.7, 0, Math.PI * 2, false); 52 | mergeContext.fillStyle = "#FFD79340"; 53 | mergeContext.fill() 54 | //mergeContext.strokeStyle = "#444444"; 55 | //mergeContext.stroke() 56 | 57 | // Draw border 58 | mergeContext.beginPath(); 59 | mergeContext.moveTo(vidWidth*position, 0); 60 | mergeContext.lineTo(vidWidth*position, vidHeight); 61 | mergeContext.closePath() 62 | mergeContext.strokeStyle = "#AAAAAA"; 63 | mergeContext.lineWidth = 5; 64 | mergeContext.stroke(); 65 | 66 | // Draw arrow 67 | mergeContext.beginPath(); 68 | mergeContext.moveTo(currX, arrowPosY - arrowWidth/2); 69 | 70 | // Move right until meeting arrow head 71 | mergeContext.lineTo(currX + arrowLength/2 - arrowheadLength/2, arrowPosY - arrowWidth/2); 72 | 73 | // Draw right arrow head 74 | mergeContext.lineTo(currX + arrowLength/2 - arrowheadLength/2, arrowPosY - arrowheadWidth/2); 75 | mergeContext.lineTo(currX + arrowLength/2, arrowPosY); 76 | mergeContext.lineTo(currX + arrowLength/2 - arrowheadLength/2, arrowPosY + arrowheadWidth/2); 77 | mergeContext.lineTo(currX + arrowLength/2 - arrowheadLength/2, arrowPosY + arrowWidth/2); 78 | 79 | // Go back to the left until meeting left arrow head 80 | mergeContext.lineTo(currX - arrowLength/2 + arrowheadLength/2, arrowPosY + arrowWidth/2); 81 | 82 | // Draw left arrow head 83 | mergeContext.lineTo(currX - arrowLength/2 + arrowheadLength/2, arrowPosY + arrowheadWidth/2); 84 | mergeContext.lineTo(currX - arrowLength/2, arrowPosY); 85 | mergeContext.lineTo(currX - arrowLength/2 + arrowheadLength/2, arrowPosY - arrowheadWidth/2); 86 | mergeContext.lineTo(currX - arrowLength/2 + arrowheadLength/2, arrowPosY); 87 | 88 | mergeContext.lineTo(currX - arrowLength/2 + arrowheadLength/2, arrowPosY - arrowWidth/2); 89 | mergeContext.lineTo(currX, arrowPosY - arrowWidth/2); 90 | 91 | mergeContext.closePath(); 92 | 93 | mergeContext.fillStyle = "#AAAAAA"; 94 | mergeContext.fill(); 95 | 96 | 97 | 98 | } 99 | requestAnimationFrame(drawLoop); 100 | } 101 | } 102 | 103 | Number.prototype.clamp = function(min, max) { 104 | return Math.min(Math.max(this, min), max); 105 | }; 106 | 107 | 108 | function resizeAndPlay(element) 109 | { 110 | var cv = document.getElementById(element.id + "Merge"); 111 | cv.width = element.videoWidth/2; 112 | cv.height = element.videoHeight; 113 | element.play(); 114 | element.style.height = "0px"; // Hide video without stopping it 115 | 116 | playVids(element.id); 117 | } 118 | 119 | 120 | function raw(element) 121 | { 122 | var cv = document.getElementById(element.id + "Merge"); 123 | cv.width = element.videoWidth/2; 124 | cv.height = element.videoHeight; 125 | element.play(); 126 | element.style.height = "0px"; // Hide video without stopping it 127 | 128 | playVids(element.id); 129 | } 130 | --------------------------------------------------------------------------------