This is a package for LiDARTag, described in paper: LiDARTag: A Real-Time Fiducial Tag System for Point Clouds

Overview

LiDARTag

Overview

This is a package for LiDARTag, described in paper: LiDARTag: A Real-Time Fiducial Tag System for Point Clouds (PDF)(arXiv). This work is accepted by IEEE Robotics and Automation Letters and published at (here).

Image-based fiducial markers are useful in problems such as object tracking in cluttered or textureless environments, camera (and multi-sensor) calibration tasks, and vision-based simultaneous localization and mapping (SLAM). However, the state-of-the-art fiducial marker detection algorithms rely on the consistency of the ambient lighting. To the best of our knowledge, there are no existing fiducial markers for point clouds.

This paper introduces LiDARTag, a novel fiducial tag design and detection algorithm suitable for LiDAR point clouds. The proposed method runs in real-time and can process data at 100 Hz, which is faster than the currently available LiDAR sensor frequencies. Additionally, the software works with different marker sizes in cluttered indoors and spacious outdoors, even when it is entirely dark. Because of the LiDAR sensors' nature, rapidly changing ambient lighting will not affect the detection of a LiDARTag. Therefore, LiDARTag can be used in tandem with camera-based markers to address the issue of images being sensitive to ambient lighting.

  • Author: Jiunn-Kai (Bruce) Huang, Shoutian Wang, Maani Ghaffari, and Jessy W. Grizzle
  • Maintainer: Bruce JK Huang, brucejkh[at]gmail.com
  • Affiliation: The Biped Lab, the University of Michigan

This package has been tested under [ROS] Melodic and Ubuntu 18.04.
[Note] More detailed introduction will be updated shortly. Sorry for the inconvenient!
[Issues] If you encounter any issues, I would be happy to help. If you cannot find a related one in the existing issues, please open a new one. I will try my best to help!

Abstract

Image-based fiducial markers are useful in problems such as object tracking in cluttered or textureless environments, camera (and multi-sensor) calibration tasks, and vision-based simultaneous localization and mapping (SLAM). The state-of-the-art fiducial marker detection algorithms rely on the consistency of the ambient lighting. This paper introduces LiDARTag, a novel fiducial tag design and detection algorithm suitable for light detection and ranging (LiDAR) point clouds. The proposed method runs in real-time and can process data at 100 Hz, which is faster than the currently available LiDAR sensor frequencies. Because of the LiDAR sensors' nature, rapidly changing ambient lighting will not affect the detection of a LiDARTag; hence, the proposed fiducial marker can operate in a completely dark environment. In addition, the LiDARTag nicely complements and is compatible with existing visual fiducial markers, such as AprilTags, allowing for efficient multi-sensor fusion and calibration tasks. We further propose a concept of minimizing a fitting error between a point cloud and the marker's template to estimate the marker's pose. The proposed method achieves millimeter error in translation and a few degrees in rotation. Due to LiDAR returns' sparsity, the point cloud is lifted to a continuous function in a reproducing kernel Hilbert space where the inner product can be used to determine a marker's ID. The experimental results, verified by a motion capture system, confirm that the proposed method can reliably provide a tag's pose and unique ID code. The rejection of false positives is validated on the Google Cartographer dataset and the outdoor Honda H3D datasets. All implementations are coded in C++ and are available at: https://github.com/UMich-BipedLab/LiDARTag.

Video

Please checkout the introduction video. It highlights some important keypoints in the paper!

Quick View

LiDAR-based markers can be used in tandem with camera-based markers to address the issue of images being sensitive to ambient lighting. LiDARTags have been successfully applied to LiDAR-camera extrinsic calibration (paper, GitHub). This figure shows a visualization of LiDARTags of two different sizes in a full point cloud scan.

This system runs in real-time (over 100 Hz) while handling a full scan of the point cloud; it achieves millimeter accuracy in translation and a few degrees of error in rotation. The tag decoding accuracy is 99.7%.

Why LiDAR?

Robust to lighting!! The following shows LiDARTags are detected in several challenging lighting conditions:

Dingy environment

Completely dark environment

Half tag being overexposed

Rapid changing ambient light

Overall pipeline

The system contains three parts: tag detection, pose estimation, and tag decoding. The detection step takes an entire LiDAR scan (up to 120,000 points from a 32-Beam Velodyne ULTRA Puck LiDAR) and outputs collections of likely payload points of the LiDARTag. Next, a tag's optimal pose minimizes the -inspired cost in (8), though the rotation of the tag about a normal vector to the tag may be off by or and will be resolved in the decoding process. The tag's ID is decoded with a pre-computed function library. The decoded tag removes the rotation ambiguity about the normal.

Package Analysis

We present performance evaluations of the LiDARTag where ground truth data are provided by a motion capture system with 30 motion capture cameras. We also extensively analyze each step in the system with spacious outdoor and cluttered indoor environments. Additionally, we report the rate of false positives validated on the indoor Google Cartographer dataset and the outdoor Honda H3D datasets.

Pose and Decoding Analysis

Decoding accuracy of the RKHS method and pose accuracy of the fitting method. The ground truth is provided by a motion capture system with 30 motion capture cameras. The distance is in meters. The translation error is in millimeters and rotation error is the misalignment angle, (23), in degrees.

Computation Time of Each Step Analysis

This table averages all the datasets we collected and describes computation time of each step for indoors and outdoors.

Cluster Rejection Analysis

This table takes into account all the data we collected and shows numbers of rejected clusters in each step in different scenes. Additionally, we also report false positive rejection for Google Cartographer dataset and Honda H3D datasets.

Double-Sum Analysis

The original double sum in (18) is too slow to achieve a real-time application. This table compares different methods to compute the double sum, in which the TBB stands for Threading Building Blocks library from Intel. Additionally, we also apply a k-d tree data structure to speed up the querying process; the k-d tree, however, does not produce fast enough results. The unit in the table is milliseconds.

False Positives Analysis

This table shows the numbers of false positive rejection of the proposed algorithm. We validated the rejection rate on the indoor Google Cartographer dataset and the outdoor Honda H3D datasets. The former has two VLP-16 Velodyne LiDAR and the latter has one 64-beam Velodyne LiDAR.

Required Libraries / Packages

Those are the packages used in the LiDARTag package. It seems many but if you follow my steps, it should take you no more than 30 mins to instal them (including building time!). It took me awhile to get everything right. I summarize how I installed them here. However, you may choose any way you want to install them.

  1. Please install ROS Melodic.
  2. Please install TBB library. You may need to modify the CMakeLists.txt according to your installation.
  3. Please install NLopt. You may need to midify the CMakeLists.txt according to your installation.
  4. Please download LiDARTag_msgs and place them under your catkin workspace.
  5. Plesae ensure you have a correct Eigen Library on your system by downloading it from the GitLab and checkout 6f0f6f792e441c32727ed945686fefe02e6bdbc6. Any commit older than this should also work.

Installation of Related Libraries

ROS Melodic

Please directly follow the instruction on the official website (here).

TBB library

Installation

Original TBB package from Intel does not support CMake; I, therefore, use another repository that supports CMake to make my life easier.

git clone https://github.com/wjakob/tbb
mkdir build;
cd build;
cmake ..;
cmake --build . --config Release -- -j 6;
sudo cmake --build . --target install
Notes

Ensure the followings in the CMakeList.txt are correct:

  1. FindTBB.cmake is under LiDARTag/cmake/
  2. LIST(APPEND CMAKE_MODULE_PATH "YOUR_PATH/LiDARTag/cmake/")
    • Please change YOUR_PATH to your path to the LiDARTag package (something like this: catkin/src/LiDARTag/cmake).

NLopt library

Installation

Please direct follow the instruction on the official website (here) or as follow:

git clone git://github.com/stevengj/nlopt
cd nlopt
mkdir build
cd build
cmake ..
make
sudo make install

LiDARTag package

  1. Once you place LiDARTag_msgs under your catkin workspace and installed all the required libraries, you can directly catkin_make the package.
  2. source devel/setup.bash
  3. roslaunch lidartag LiDARTag_twotags.launch
  4. rosbag play -l -q bagfile.bag

Datasets and Results

Quantitative results:

If you would like to see how the tables in the paper are generated, please follow as below:

  1. Download this folder.
  2. Put them under LiDARTag/matlab/paper_data/
  3. Run genTable.m located at LiDARTag/matlab/

To regenerate results on the paper from scratch, please download the two datasets below:

  1. Please download bagfiles from here.
  2. Please download motion capture data from here
  3. change the output_path in the launch file
  4. roslaunch lidartag LiDARTag_threetags.launch
Note

The target sizes in the quantitative result folder are 1.22.

Qualitative results:

  1. Please download bagfiles from here.
  2. roslaunch lidartag LiDARTag_twotags.launch
Note

The target sizes in the qualitative result folder are 0.8051, 0.61.

False positive rejection:

Please download Google Cartographer dataset and Honda H3D datasets. We also provide different launch files (cartographer.launch, H3D.launch) for different datasets due to different published LiDAR topics and different output_path. I also wrote my own parsing script to pass bin files to rosbag. Please let me know if anyone needs it.

Running

  1. Please download qualitative bagfiles from here.
  2. catkin_make the package.
  3. source devel/setup.bash
  4. roslaunch lidartag LiDARTag_twotags.launch
  5. rosbag play -l -q bagfile.bag
  6. To see the results, rosrun rviz rviz. You can directly open LiDARTag.rviz under LiDARTag/rviz/ folder.
Notes

This package provides several launch files that you can directly run the package.
Please remember to change the tag_size_list in a launch file according to your target sizes or which bag file you are playing, or what marker sizes you have.
Different launch files:
-- LiDARTag_smallest.launch: only the smallest tag (0.61)
-- LiDARTag_twotags.launch: two smaller tags (0.61, 0.8)
-- LiDARTag_threetags.launch: all tags (0.8, 0.61, 1.22)
Please note that, the clearance around the markers should larger than , where is the size of the largest marker. Therefore, it is recommended to use smaller tags in indoor environments.

Building Your Markers


We provide tag16h6c5 from AprilTag3 with three sizes (0.61, 0.85, 1.2).
If you want to use the provided markers, it is easy:

  1. Attach a fiducial marker to a squared cardboard or plexiglass and place the marker inside the yellow region.
    • Note: The sizes must be one of 0.61, 0.805, 1.22 meter, or you have to regenerate the function dictionary. If so, please follow here.
  2. Find a 3D object to support your marker. It could be a box or an easel.
    • Please note that, the clearance around the markers should larger than , where is the size of the largest marker. Therefore, it is recommended to use smaller tags in indoor environments.
  3. Follow these steps to run the package.

Building Your Own Customized Markers

If you would like to use your own customized markers (i.e. different types of markers or different sizes), please follow these steps:
I. Build your function dictionary:

  1. git clone https://github.com/UMich-BipedLab/matlab_utils
  2. Add matlab_utils into build_LiDARTag_library.m or add matlab_utils into your MATLAB path.
  3. Edit opts.img_path in build_LiDARTag_library.m according to where you put images of your fiducial markers.
  4. Measure the size of your marker ()
  5. Open build_LiDARTag_library.m in LiDARTag/matlab/function_dictionary/. Change opts.target_size_ to your marker size and run build_LiDARTag_library.m to generate your function library.
  6. Put the generated function dictuionary into LiDARTag/lib/
  7. When placing the generated function dictionary in LiDARTag/lib/, please put different sizes into different sub-folders (0, 1, 2, 3, ...) and put them in ascending order. For example, if you have three sizes (0.6, 0.8, 1.2), then you will have three sub-folders (0, 1, 2) inside the lib/ folder. Please place them as follow:
    • LiDARTag/lib/0/: put 0.6-size here
    • LiDARTag/lib/1/: put 0.8-size here
    • LiDARTag/lib/2/: put 1.2-size here

II. Follow Building Your Markers

Note

All the functions that are used for testing RKHS are all released in LiDARTag/matlab/function_dictionary/

Parameters of launch files

We split the parameters to two different launch files: LiDARTag_outdoor.launch and LiDARTag_master.launch. The front contains the most common tunables for different environments such as indoor or outdoor. The latter includes more parameters that you usually need to change for your system only once and just leave them there.

LiDARTag_outdoor.launch

feature clustering
  • nearby_factor
    Value used to determine if two points are near to each other
  • linkage_tunable
    Value used to compute the linkage criteria
cluster validation
  • max_outlier_ratio
    Value used to validate clusters during checking outliers in plane fitting
  • tag_size_list
    List of possible sizes of tag

LiDARTag_master.launch

System Mode

  • mark_cluster_validity
    whether to validate clusters according to different conditions
  • plane_fitting
    whether to validate clusters according to the result of plane_fitting
  • optimize_pose
    Whether to optimize poses via reducing the cost function
  • decode_id
    Whether to decode IDs
  • collect_data
    Whether to publish detected PCs
  • num_threads
    The number of threads used for TBB
  • print_info
    Whether to log status in ros_info_stream

Debugging Mode

  • debug_info
    Whether to log debug information in ros_debug_stream
  • debug_time
    Whether to compute time for different parts
  • debug_decoding_time
    Whether to log time for decoding IDs
  • log_data
    Whether to save status information into txt file

LiDAR Specification

  • has_ring
    Whether input data has ring information for each point
  • estimate_ring
    Whether to estimate ring number for each point

Solvers for Pose Optimization

  • optimization_solver (default: 8)
    Which optimization solver to use for optimizing the cost function of a pose.

    • Below is numerical gradient-based methods
      1: opt_method = nlopt::LN_PRAXIS;
      2: opt_method = nlopt::LN_NEWUOA_BOUND;
      3: opt_method = nlopt::LN_SBPLX; // recommended
      4: opt_method = nlopt::LN_BOBYQA;
      5: opt_method = nlopt::LN_NELDERMEAD;
      6: opt_method = nlopt::LN_COBYLA;
    • Below is analytical gradient-based methods
      7: opt_method = nlopt::LD_SLSQP; // recommended 200Hz
      8: opt_method = nlopt::LD_MMA; // recommended 120Hz
      9: opt_method = nlopt::LD_TNEWTON_PRECOND_RESTART; // fail 90%
      10: opt_method = nlopt::LD_TNEWTON_PRECOND; // fail 90%
      11: opt_method = nlopt::LD_TNEWTON_RESTART; // fail 80%
      12: opt_method = nlopt::LD_TNEWTON; // fail 90%
      13: opt_method = nlopt::LD_LBFGS; // fail 90%
      14: opt_method = nlopt::LD_VAR1; // fail 90%
      15: opt_method = nlopt::LD_VAR2; // fail 90%
  • euler_derivative
    Whether to use euler derivative or lie group derivative in optimization

  • optimize_up_bound
    Value used for constraints in optimization

  • optimize_low_bound
    Value used for constraints in optimization

Decode Method

  • decode_method (default: 2)
    Which decoding method to use:
    0: naive decoder
    1: Weighted Gaussian
    2: RKHS
  • decode_mode (default: 5)
    Which mode to use: 0: single thread: original double sum
    1: single thread: convert to matrices
    2: single thread: convert matrices to vectors
    3: c++ thread (works for each point for a thread but not for blobs of points for a thread)
    4: Multi-threading: Original double sum using TBB
    5: Multi-threading: Vector form using TBB without scheduling
    6: Multi-threading: Vector form using TBB with manual scheduling
    7: Multi-threading: Vector form using TBB with TBB scheduling
    8: Single thread: using KDTree

Tunable

feature clustering
  • distance_bound
    Value used to construct a cube and only detect the tag inside this cube
  • depth_bound
    Value used to detect feature points compared with depth gradients
  • num_points_for_plane_feature
    number of points used for detection of feature points
cluster validation
  • min_return_per_grid
    Minimum number of points in each grid (below this number, the cluster will be invalid)
  • optimize_percentage
    Value used to validate the result of pose estimation via checking cost value
  • payload_intensity_threshold
    Value used to detect boundary points on the cluster via intensity gradient
  • points_threshold_factor
  • distance_to_plane_threshold
    Value used for plane fitting for a cluster
  • minimum_ring_boundary_points
    Minimum number of boundary points on each ring in the cluster
  • coa_tunable
    Value used to validate the result of pose estimation via checking coverage area
  • tagsize_tunable
    Value used to estimate the size of tag

Citations

The detail is described in: LiDARTag: A Real-Time Fiducial Tag for Point Clouds, Jiunn-Kai Huang, Shoutian Wang, Maani Ghaffari, and Jessy W. Grizzle. (PDF) (arXiv) (here)

@ARTICLE{HuangLiDARTag2020,
  author={Huang, Jiunn-Kai and Wang, Shoutian and Ghaffari, Maani and Grizzle, Jessy W.},
  journal={IEEE Robotics and Automation Letters}, 
  title={LiDARTag: A Real-Time Fiducial Tag System for Point Clouds},
  year={2021},
  volume={6},
  number={3},
  pages={4875-4882},
  doi={10.1109/LRA.2021.3070302}}
Comments
  • Error about Eigen::all in lidartag_decode.cc

    Error about Eigen::all in lidartag_decode.cc

    hello

    Once catkin_make. I'm having trouble with the following error.

    /home/robotics/catkin_ws/src/LiDARTag/src/lidartag_decode.cc:841:47: error: ‘all’ is not a member of ‘Eigen’ Eigen::MatrixXf test_mat = pc1(Eigen::all, indices); ^~~ /home/robotics/catkin_ws/src/LiDARTag/src/lidartag_decode.cc:841:47: note: suggested alternatives: In file included from /usr/include/boost/algorithm/string.hpp:21:0, from /usr/include/pcl-1.8/pcl/io/boost.h:66, from /usr/include/pcl-1.8/pcl/io/file_io.h:43, from /usr/include/pcl-1.8/pcl/io/pcd_io.h:44, from /home/robotics/catkin_ws/src/LiDARTag/include/lidartag.h:56, from /home/robotics/catkin_ws/src/LiDARTag/src/lidartag_decode.cc:37: /usr/include/boost/algorithm/string/predicate.hpp:438:21: note: ‘boost::algorithm::all’ inline bool all( ^~~ /usr/include/boost/algorithm/string/predicate.hpp:438:21: note: ‘boost::algorithm::all’ /home/robotics/catkin_ws/src/LiDARTag/src/lidartag_decode.cc: In lambda function: /home/robotics/catkin_ws/src/LiDARTag/src/lidartag_decode.cc:1030:47: error: ‘all’ is not a member of ‘Eigen’ Eigen::MatrixXf test_mat = pc1(Eigen::all, indices); ^~~

    I don't think Eigen::all is working well. What should I do?

    opened by RyoHinata-jp 14
  • error: ‘all’ is not a member of ‘Eigen’

    error: ‘all’ is not a member of ‘Eigen’

    Dear Authors, After installing ROS, my Eigen version is 3.3.4, I also installed version 3.3.9. But, when I compile this package but got the error about "error: ‘all’ is not a member of ‘Eigen’", as shown,

    LiDARTag/src/LiDARTag/src/lidartag_decode.cc:841:47: error: ‘all’ is not a member of ‘Eigen’ Eigen::MatrixXf test_mat = pc1(Eigen::all, indices);

    Would you help me solve the problem? Thank you,

    opened by NamDinhRobotics 8
  • Limitations of tag extraction method

    Limitations of tag extraction method

    hello,

    I test the lidartag in a corridor, the tag is placed in the center, but the extracted cluster often contains points on the wall, like the picture (I displayed the clusters one by one).

    2020-04-27 23-40-31屏幕截图

    how to change some paramters?

    I think the _updateCluster function, will make a cluster bigger and biger in a bad trend,I want to improve it, have you some advice?

    Thanks a lot!

    opened by plumewind 7
  • How to add ring-msg for my rslidar?

    How to add ring-msg for my rslidar?

    hello,

    my rslidar is 32, but no ring. I want to add ring in the lidar_tag.cc:

    lines496-500 in _getOrderBuff(): pcl::PointCloud<PointXYZRI>::Ptr PclPointcloud(new pcl::PointCloud<PointXYZRI>); pcl::fromROSMsg(*msg, *PclPointcloud);

    change to this: pcl::PointCloud<PointXYZRI>::Ptr PclPointcloud(new pcl::PointCloud<PointXYZRI>); pcl::PointCloud<pcl::PointXYZI>::Ptr PclPointcloud_raw(new pcl::PointCloud<pcl::PointXYZI>); pcl::fromROSMsg(*msg, *PclPointcloud_raw); _addRing(PclPointcloud_raw, PclPointcloud);

    but get error: `[ INFO] [1586340483.356691067]: Start edge extraction on rslidar-32

    points size 53119

    test 1 in _getOrderBuff()

    test 1 in _mainLoop()

    [LiDARTag/lidar_tag-3] process has died [pid 24622, exit code -11, cmd /home/bran/catkin_tagcalib/devel/lib/lidar_tag/lidar_tag_main __name:=lidar_tag __log:=/home/bran/.ros/log/cfd224c6-7980-11ea-8d4b-dc71967741ec/LiDARTag-lidar_tag-3.log].

    log file: /home/bran/.ros/log/cfd224c6-7980-11ea-8d4b-dc71967741ec/LiDARTag-lidar_tag-3*.log

    first: 1 second: 1 Third: 18

    [ INFO] [1586340484.094978105]: Apriltag got wrong tags

    ^C[apriltag3ROS-4] killing on exit [sync_cam_lidar-2] killing on exit The apriltag3_ros is over! [rosout-1] killing on exit [master] killing on exit shutting down processing monitor... ... shutting down processing monitor complete`

    Should I ignore something? Can you help me?Thanks a lot.

    opened by plumewind 7
  • Sign inversion in R matrix

    Sign inversion in R matrix

    Dear Authors, Thank you for your great work. I tested this repository on our lidartag, I found detection is often failed because initial pose is not stable. I debugged and found signs of some values in R matrix are inverted in fitGrid_new function. I fixed GridVertices and payload_vertices, these are augments of fitGrid_new function, but the sign inversion are occurred. If I fix R matrix, sign inversion is not occurred and initial pose is stable. below is the video of the test(Payload_vertices is not fixed in this case) We can find

    • Pose optimization status is 1 if R element of 1 line 1 row is negative.
    • pose optimization status is 2 or -3 if R element of 1 line 1 row is positive.

    https://user-images.githubusercontent.com/32808802/127618912-ecdf6d86-34b5-4b48-a9d7-f81a712ecff9.mp4

    I reproduced this problem using sample bag, ccw_6m.bag on default setting.

    https://user-images.githubusercontent.com/32808802/127620627-8cbeb46f-9073-4ee3-b46e-0e3a65dca707.mp4

    Do you have any suggestion?

    thanks,

    opened by sgk-000 6
  • Inquiry into vertices definition

    Inquiry into vertices definition

    Sorry to bother you again. But I just compared the vertices estimated by my method and the results in your paper data. I found the x coordinates are quite close and the error is within millimeters. But the dimension of the marker given by my system is smaller than yours. So I'm wondering if we are using the same definition of vertices. According to your paper, it seems the vertices are the ones of the object. image Hence, I feel like the vertices you are using refer to the red points instead of the blue points. I'm wondering if it is correct? image

    opened by yorklyb 4
  • error: ‘all’ is not a member of ‘Eigen’

    error: ‘all’ is not a member of ‘Eigen’

    Hi, Thanks for your package. I download the eigen3 from gitlab and checkout the SHA1 you use, but the error always exists when compiling. I am sure the version being used is the right one because I assign the eigen 3.3.9 in find_package and it indeed find the right version as below: Found TBB: /usr/local/include (found version "2020.2") -- =============================================TBB FOUND -- ===============================TBB include_dirs: /usr/local/include -- ===============================TBB includes: -- ===============================TBB libs: -- ===============================TBB libraries: /usr/local/lib/libtbb.so -- ===============================TBB libraries: /usr/local/lib/libtbb.so -- ===============================TBB libs: -- ===============================TBB defs: -- =============================================Eigen final path: /usr/local/include/eigen3
    Besides, the compile of my small demo which also uses the Eigen::all is successful. The small demo has almost the same CMakeLists.txt as your package. It means that the version of the found eigen3 is right but can not work in your package. Below is the CMakeLists.txt of the small demo:
    cmake_minimum_required(VERSION 2.8 FATAL_ERROR)

    project(Eigen_test)

    find_package(Eigen3 3.3.90 REQUIRED)

    include_directories(${EIGEN3_INCLUDE_DIRS}) message(STATUS "=============================================Eigen Path : ${EIGEN3_INCLUDE_DIRS}")

    add_executable(Eigen_test Eigen_test.cpp)
    and this is my small demo:
    #include "Eigen/Core" #include <vector> #include <iostream>

    int main(void) { std::vector<int> ind{4,2,5,5,3}; Eigen::MatrixXi A = Eigen::MatrixXi::Random(4,6); std::cout << "Initial matrix A:\n" << A << "\n\n"; std::cout << "A(all,ind):\n" << A(Eigen::all,ind) << "\n\n"; return 0; }
    and this is the compile result:
    -- =============================================Eigen Path : /usr/local/include/eigen3 -- Configuring done -- Generating done -- Build files have been written to: /home/zhehe/test/Eigen_test/build

    [ 50%] Building CXX object CMakeFiles/Eigen_test.dir/Eigen_test.cpp.o [100%] Linking CXX executable Eigen_test [100%] Built target Eigen_test
    Can you please help me sovle this issue? Thank you very much.

    opened by zzhh00 3
  • Are other tags  useful?

    Are other tags useful?

    hello,

    I saw the newer pkg, only for tag49h14 and tag16h5, can other tags ?

    I read the tag16h5_create(), find it is not look like apriltag decoding, because their tag16h5.cc are different. Can I add for myself ? How to add?

    Can you help me? Thanks a lot.

    opened by plumewind 3
  • The link to the motion capture data is invalid

    The link to the motion capture data is invalid

    Hi Jiunn-Kai, I'm trying to get to the motion capture data, however, I found that the link is not valid anymore. It shows me a 404 error. Could you please fix it when you see this? Thanks!

    opened by yorklyb 2
  • How to print the tags.

    How to print the tags.

    Hello,

    thanks for taking the time to check out my post. I want some help for printing the targets, more specifically is unclear to me how to generate those tags. Please, can you provide some information on that? I see that you provide some information about the targets at the lib folder but it is unclear tome how to use it. Also, I understand that I need to have matlab installed in order to print custom tags, is that right?

    Thanks in advance!

    opened by Mikor-mkr 2
  • error: 'all' is not a member of 'Eigen'

    error: 'all' is not a member of 'Eigen'

    I looked at every other issue related to this and tried the recommended steps. Still no resolution

                     from /home/sdcnlab/install/workspace/src/LiDARTag/src/lidartag_decode.cc:37:
    /usr/local/include/tbb/tbb.h:21:154: note: ‘#pragma message: TBB Warning: tbb.h contains deprecated functionality. For details, please see Deprecated Features appendix in the TBB reference manual.’
       21 |  please see Deprecated Features appendix in the TBB reference manual.")
          |                                                                       ^
    
    /home/sdcnlab/install/workspace/src/LiDARTag/src/lidartag_decode.cc: In member function ‘void BipedLab::LiDARTag::computeFunctionVectorInnerProductThreading(const MatrixXf&, const int&, const MatrixXf&, const int&, const float&, const float&, const float&, float&)’:
    /home/sdcnlab/install/workspace/src/LiDARTag/src/lidartag_decode.cc:843:47: error: ‘all’ is not a member of ‘Eigen’
      843 |         Eigen::MatrixXf test_mat = pc1(Eigen::all, indices);
          |                                               ^~~
    /home/sdcnlab/install/workspace/src/LiDARTag/src/lidartag_decode.cc:843:47: note: suggested alternatives:
    In file included from /usr/include/boost/algorithm/string.hpp:21,
                     from /usr/include/pcl-1.8/pcl/io/boost.h:66,
                     from /usr/include/pcl-1.8/pcl/io/file_io.h:43,
                     from /usr/include/pcl-1.8/pcl/io/pcd_io.h:44,
                     from /home/sdcnlab/install/workspace/src/LiDARTag/include/lidartag.h:56,
                     from /home/sdcnlab/install/workspace/src/LiDARTag/src/lidartag_decode.cc:37:
    /usr/include/boost/algorithm/string/predicate.hpp:438:21: note:   ‘boost::algorithm::all’
      438 |         inline bool all(
          |                     ^~~
    /usr/include/boost/algorithm/string/predicate.hpp:438:21: note:   ‘boost::algorithm::all’
    /home/sdcnlab/install/workspace/src/LiDARTag/src/lidartag_decode.cc: In lambda function:
    /home/sdcnlab/install/workspace/src/LiDARTag/src/lidartag_decode.cc:1032:47: error: ‘all’ is not a member of ‘Eigen’
     1032 |         Eigen::MatrixXf test_mat = pc1(Eigen::all, indices);
          |                                               ^~~
    /home/sdcnlab/install/workspace/src/LiDARTag/src/lidartag_decode.cc:1032:47: note: suggested alternatives:
    In file included from /usr/include/boost/algorithm/string.hpp:21,
                     from /usr/include/pcl-1.8/pcl/io/boost.h:66,
                     from /usr/include/pcl-1.8/pcl/io/file_io.h:43,
                     from /usr/include/pcl-1.8/pcl/io/pcd_io.h:44,
                     from /home/sdcnlab/install/workspace/src/LiDARTag/include/lidartag.h:56,
                     from /home/sdcnlab/install/workspace/src/LiDARTag/src/lidartag_decode.cc:37:
    /usr/include/boost/algorithm/string/predicate.hpp:438:21: note:   ‘boost::algorithm::all’
      438 |         inline bool all(
          |                     ^~~
    /usr/include/boost/algorithm/string/predicate.hpp:438:21: note:   ‘boost::algorithm::all’
    LiDARTag/CMakeFiles/lidartag_main.dir/build.make:134: recipe for target 'LiDARTag/CMakeFiles/lidartag_main.dir/src/lidartag_decode.cc.o' failed
    make[2]: *** [LiDARTag/CMakeFiles/lidartag_main.dir/src/lidartag_decode.cc.o] Error 1
    CMakeFiles/Makefile2:2124: recipe for target 'LiDARTag/CMakeFiles/lidartag_main.dir/all' failed
    make[1]: *** [LiDARTag/CMakeFiles/lidartag_main.dir/all] Error 2
    Makefile:140: recipe for target 'all' failed
    make: *** [all] Error 2
    Invoking "make -j20 -l20" failed
    
    1. I only have one version of Eigen installed (latest release), I did try with several other version up to 2019 releases
    2. I tried going over all the other related issues but couldn't find a solution
    opened by AmaldevHari 2
  • Apriltag2 or 3?

    Apriltag2 or 3?

    Hi, Thanks your great project. Recently I wanna use ouster lidar(os1-64) to detect tags, But I got a few problems.

    1. In README we provide tag16h6c5 from AprilTag3 with three sizes (0.61, 0.85, 1.2)., The size means t in the below picture? image
    2. I check the AprilTag3 here image but I found it is not the same in your paper, also in your provide bags. image image The tag 0 and tag 4 in apriltag3 (tag16h5) is not the same with above picture. so I check the code betwen lidartag here and apriltag here, I found that your file is the same with apriltag2 here but not 3. but I found your provide tags is apriltag3. so I'm a little confused about that which apriltags to use.
    opened by TurtleZhong 0
  • ROS2 Port

    ROS2 Port

    Dear authors, As part of our sensor calibration toolkit, we in Tier IV are using lidartags for camera-lidar calibration.

    Having finished the main part of our development we are wondering if you would be interested in accepting a PR centering in a ROS2 port. However, in addition to the ROS2 migration, we ended up making additional changes to suit our use cases.

    The main changes are:

    • ROS2 migration
    • Strong refactoring
    • Focus on detection accuracy rather than speed
    • Improved initial tag detection through modified filters and custom RANSACs.

    Thanks or the great project !

    opened by knzo25 2
Owner
University of Michigan Dynamic Legged Locomotion Robotics Lab
We do feedback control of bipedal robots and we do it better than anyone else.
University of Michigan Dynamic Legged Locomotion Robotics Lab
Implementation of paper "DeepTag: A General Framework for Fiducial Marker Design and Detection"

Implementation of paper DeepTag: A General Framework for Fiducial Marker Design and Detection. Project page: https://herohuyongtao.github.io/research/

Yongtao Hu 46 Dec 12, 2022
Code for "PV-RAFT: Point-Voxel Correlation Fields for Scene Flow Estimation of Point Clouds", CVPR 2021

PV-RAFT This repository contains the PyTorch implementation for paper "PV-RAFT: Point-Voxel Correlation Fields for Scene Flow Estimation of Point Clou

Yi Wei 43 Dec 5, 2022
Not All Points Are Equal: Learning Highly Efficient Point-based Detectors for 3D LiDAR Point Clouds (CVPR 2022, Oral)

Not All Points Are Equal: Learning Highly Efficient Point-based Detectors for 3D LiDAR Point Clouds (CVPR 2022, Oral) This is the official implementat

Yifan Zhang 259 Dec 25, 2022
Fog Simulation on Real LiDAR Point Clouds for 3D Object Detection in Adverse Weather

LiDAR fog simulation Created by Martin Hahner at the Computer Vision Lab of ETH Zurich. This is the official code release of the paper Fog Simulation

Martin Hahner 110 Dec 30, 2022
Pip-package for trajectory benchmarking from "Be your own Benchmark: No-Reference Trajectory Metric on Registered Point Clouds", ECMR'21

Map Metrics for Trajectory Quality Map metrics toolkit provides a set of metrics to quantitatively evaluate trajectory quality via estimating consiste

Mobile Robotics Lab. at Skoltech 31 Oct 28, 2022
This project is the official implementation of our accepted ICLR 2021 paper BiPointNet: Binary Neural Network for Point Clouds.

BiPointNet: Binary Neural Network for Point Clouds Created by Haotong Qin, Zhongang Cai, Mingyuan Zhang, Yifu Ding, Haiyu Zhao, Shuai Yi, Xianglong Li

Haotong Qin 59 Dec 17, 2022
This repo is a PyTorch implementation for Paper "Unsupervised Learning for Cuboid Shape Abstraction via Joint Segmentation from Point Clouds"

Unsupervised Learning for Cuboid Shape Abstraction via Joint Segmentation from Point Clouds This repository is a PyTorch implementation for paper: Uns

Kaizhi Yang 42 Dec 9, 2022
The official implementation of ICCV paper "Box-Aware Feature Enhancement for Single Object Tracking on Point Clouds".

Box-Aware Tracker (BAT) Pytorch-Lightning implementation of the Box-Aware Tracker. Box-Aware Feature Enhancement for Single Object Tracking on Point C

Kangel Zenn 5 Mar 26, 2022
Code for the paper "Spatio-temporal Self-Supervised Representation Learning for 3D Point Clouds" (ICCV 2021)

Spatio-temporal Self-Supervised Representation Learning for 3D Point Clouds This is the official code implementation for the paper "Spatio-temporal Se

Hesper 63 Jan 5, 2023
This is the code repository implementing the paper "TreePartNet: Neural Decomposition of Point Clouds for 3D Tree Reconstruction".

TreePartNet This is the code repository implementing the paper "TreePartNet: Neural Decomposition of Point Clouds for 3D Tree Reconstruction". Depende

刘彦超 34 Nov 30, 2022
Code for the paper SphereRPN: Learning Spheres for High-Quality Region Proposals on 3D Point Clouds Object Detection, ICIP 2021.

SphereRPN Code for the paper SphereRPN: Learning Spheres for High-Quality Region Proposals on 3D Point Clouds Object Detection, ICIP 2021. Authors: Th

Thang Vu 15 Dec 2, 2022
Public repository of the 3DV 2021 paper "Generative Zero-Shot Learning for Semantic Segmentation of 3D Point Clouds"

Generative Zero-Shot Learning for Semantic Segmentation of 3D Point Clouds Björn Michele1), Alexandre Boulch1), Gilles Puy1), Maxime Bucher1) and Rena

valeo.ai 15 Dec 22, 2022
(CVPR 2021) PAConv: Position Adaptive Convolution with Dynamic Kernel Assembling on Point Clouds

PAConv: Position Adaptive Convolution with Dynamic Kernel Assembling on Point Clouds by Mutian Xu*, Runyu Ding*, Hengshuang Zhao, and Xiaojuan Qi. Int

CVMI Lab 228 Dec 25, 2022
《A-CNN: Annularly Convolutional Neural Networks on Point Clouds》(2019)

A-CNN: Annularly Convolutional Neural Networks on Point Clouds Created by Artem Komarichev, Zichun Zhong, Jing Hua from Department of Computer Science

Artёm Komarichev 44 Feb 24, 2022
Official PyTorch implementation of CAPTRA: CAtegory-level Pose Tracking for Rigid and Articulated Objects from Point Clouds

CAPTRA: CAtegory-level Pose Tracking for Rigid and Articulated Objects from Point Clouds Introduction This is the official PyTorch implementation of o

Yijia Weng 96 Dec 7, 2022
(CVPR 2021) Back-tracing Representative Points for Voting-based 3D Object Detection in Point Clouds

BRNet Introduction This is a release of the code of our paper Back-tracing Representative Points for Voting-based 3D Object Detection in Point Clouds,

null 86 Oct 5, 2022
Self-Supervised Learning for Domain Adaptation on Point-Clouds

Self-Supervised Learning for Domain Adaptation on Point-Clouds Introduction Self-supervised learning (SSL) allows to learn useful representations from

Idan Achituve 66 Dec 20, 2022
Rendering Point Clouds with Compute Shaders

Compute Shader Based Point Cloud Rendering This repository contains the source code to our techreport: Rendering Point Clouds with Compute Shaders and

Markus Schütz 460 Jan 5, 2023
Uncertainty-aware Semantic Segmentation of LiDAR Point Clouds for Autonomous Driving

SalsaNext: Fast, Uncertainty-aware Semantic Segmentation of LiDAR Point Clouds for Autonomous Driving Abstract In this paper, we introduce SalsaNext f

null 308 Jan 4, 2023