Code Monkey home page Code Monkey logo

fast_lio's Introduction

Related Works and Extended Application

SLAM:

  1. ikd-Tree: A state-of-art dynamic KD-Tree for 3D kNN search.
  2. R2LIVE: A high-precision LiDAR-inertial-Vision fusion work using FAST-LIO as LiDAR-inertial front-end.
  3. LI_Init: A robust, real-time LiDAR-IMU extrinsic initialization and synchronization package..
  4. FAST-LIO-LOCALIZATION: The integration of FAST-LIO with Re-localization function module.

Control and Plan:

  1. IKFOM: A Toolbox for fast and high-precision on-manifold Kalman filter.
  2. UAV Avoiding Dynamic Obstacles: One of the implementation of FAST-LIO in robot's planning.
  3. UGV Demo: Model Predictive Control for Trajectory Tracking on Differentiable Manifolds.
  4. Bubble Planner: Planning High-speed Smooth Quadrotor Trajectories using Receding Corridors.

FAST-LIO

FAST-LIO (Fast LiDAR-Inertial Odometry) is a computationally efficient and robust LiDAR-inertial odometry package. It fuses LiDAR feature points with IMU data using a tightly-coupled iterated extended Kalman filter to allow robust navigation in fast-motion, noisy or cluttered environments where degeneration occurs. Our package address many key issues:

  1. Fast iterated Kalman filter for odometry optimization;
  2. Automaticaly initialized at most steady environments;
  3. Parallel KD-Tree Search to decrease the computation;

FAST-LIO 2.0 (2021-07-05 Update)

Related video: FAST-LIO2, FAST-LIO1

Pipeline:

New Features:

  1. Incremental mapping using ikd-Tree, achieve faster speed and over 100Hz LiDAR rate.
  2. Direct odometry (scan to map) on Raw LiDAR points (feature extraction can be disabled), achieving better accuracy.
  3. Since no requirements for feature extraction, FAST-LIO2 can support many types of LiDAR including spinning (Velodyne, Ouster) and solid-state (Livox Avia, Horizon, MID-70) LiDARs, and can be easily extended to support more LiDARs.
  4. Support external IMU.
  5. Support ARM-based platforms including Khadas VIM3, Nivida TX2, Raspberry Pi 4B(8G RAM).

Related papers:

FAST-LIO2: Fast Direct LiDAR-inertial Odometry

FAST-LIO: A Fast, Robust LiDAR-inertial Odometry Package by Tightly-Coupled Iterated Kalman Filter

Contributors

Wei Xu 徐威Yixi Cai 蔡逸熙Dongjiao He 贺东娇Fangcheng Zhu 朱方程Jiarong Lin 林家荣Zheng Liu 刘政, Borong Yuan

1. Prerequisites

1.1 Ubuntu and ROS

Ubuntu >= 16.04

For Ubuntu 18.04 or higher, the default PCL and Eigen is enough for FAST-LIO to work normally.

ROS >= Melodic. ROS Installation

1.2. PCL && Eigen

PCL >= 1.8, Follow PCL Installation.

Eigen >= 3.3.4, Follow Eigen Installation.

1.3. livox_ros_driver

Follow livox_ros_driver Installation.

Remarks:

  • Since the FAST-LIO must support Livox serials LiDAR firstly, so the livox_ros_driver must be installed and sourced before run any FAST-LIO luanch file.
  • How to source? The easiest way is add the line source $Livox_ros_driver_dir$/devel/setup.bash to the end of file ~/.bashrc, where $Livox_ros_driver_dir$ is the directory of the livox ros driver workspace (should be the ws_livox directory if you completely followed the livox official document).

2. Build

If you want to use docker conatiner to run fastlio2, please install the docker on you machine. Follow Docker Installation.

2.1 Docker Container

User can create a new script with anyname by the following command in linux:

touch <your_custom_name>.sh

Place the following code inside the <your_custom_name>.sh script.

#!/bin/bash
mkdir docker_ws
# Script to run ROS Kinetic with GUI support in Docker

# Allow X server to be accessed from the local machine
xhost +local:

# Container name
CONTAINER_NAME="fastlio2"

# Run the Docker container
docker run -itd \
  --name=$CONTAINER_NAME \
  --user mars_ugv \
  --network host \
  --ipc=host \
  -v /home/$USER/docker_ws:/home/mars_ugv/docker_ws \
  --privileged \
  --env="QT_X11_NO_MITSHM=1" \
  --volume="/etc/localtime:/etc/localtime:ro" \
  -v /dev/bus/usb:/dev/bus/usb \
  --device=/dev/dri \
  --group-add video \
  -v /tmp/.X11-unix:/tmp/.X11-unix \
  --env="DISPLAY=$DISPLAY" \
  kenny0407/marslab_fastlio2:latest \
  /bin/bash

execute the following command to grant execute permissions to the script, making it runnable:

sudo chmod +x <your_custom_name>.sh

execute the following command to download the image and create the container.

./<your_custom_name>.sh

Script explanation:

  • The docker run command provided below creates a container with a tag, using an image from Docker Hub. The download duration for this image can differ depending on the user's network speed.
  • This command also establishes a new workspace called docker_ws, which serves as a shared folder between the Docker container and the host machine. This means that if users wish to run the rosbag example, they need to download the rosbag file and place it in the docker_ws directory on their host machine.
  • Subsequently, a folder with the same name inside the Docker container will receive this file. Users can then easily play the file within Docker.
  • In this example, we've shared the network of the host machine with the Docker container. Consequently, if users execute the rostopic list command, they will observe identical output whether they run it on the host machine or inside the Docker container."

2.2 Build from source

Clone the repository and catkin_make:

    cd ~/$A_ROS_DIR$/src
    git clone https://github.com/hku-mars/FAST_LIO.git
    cd FAST_LIO
    git submodule update --init
    cd ../..
    catkin_make
    source devel/setup.bash
  • Remember to source the livox_ros_driver before build (follow 1.3 livox_ros_driver)
  • If you want to use a custom build of PCL, add the following line to ~/.bashrc export PCL_ROOT={CUSTOM_PCL_PATH}

3. Directly run

Noted:

A. Please make sure the IMU and LiDAR are Synchronized, that's important.

B. The warning message "Failed to find match for field 'time'." means the timestamps of each LiDAR points are missed in the rosbag file. That is important for the forward propagation and backwark propagation.

C. We recommend to set the extrinsic_est_en to false if the extrinsic is give. As for the extrinsic initiallization, please refer to our recent work: Robust Real-time LiDAR-inertial Initialization.

3.1 For Avia

Connect to your PC to Livox Avia LiDAR by following Livox-ros-driver installation, then

    cd ~/$FAST_LIO_ROS_DIR$
    source devel/setup.bash
    roslaunch fast_lio mapping_avia.launch
    roslaunch livox_ros_driver livox_lidar_msg.launch
  • For livox serials, FAST-LIO only support the data collected by the livox_lidar_msg.launch since only its livox_ros_driver/CustomMsg data structure produces the timestamp of each LiDAR point which is very important for the motion undistortion. livox_lidar.launch can not produce it right now.
  • If you want to change the frame rate, please modify the publish_freq parameter in the livox_lidar_msg.launch of Livox-ros-driver before make the livox_ros_driver pakage.

3.2 For Livox serials with external IMU

mapping_avia.launch theratically supports mid-70, mid-40 or other livox serial LiDAR, but need to setup some parameters befor run:

Edit config/avia.yaml to set the below parameters:

  1. LiDAR point cloud topic name: lid_topic
  2. IMU topic name: imu_topic
  3. Translational extrinsic: extrinsic_T
  4. Rotational extrinsic: extrinsic_R (only support rotation matrix)
  • The extrinsic parameters in FAST-LIO is defined as the LiDAR's pose (position and rotation matrix) in IMU body frame (i.e. the IMU is the base frame). They can be found in the official manual.
  • FAST-LIO produces a very simple software time sync for livox LiDAR, set parameter time_sync_en to ture to turn on. But turn on ONLY IF external time synchronization is really not possible, since the software time sync cannot make sure accuracy.

3.3 For Velodyne or Ouster (Velodyne as an example)

Step A: Setup before run

Edit config/velodyne.yaml to set the below parameters:

  1. LiDAR point cloud topic name: lid_topic
  2. IMU topic name: imu_topic (both internal and external, 6-aixes or 9-axies are fine)
  3. Set the parameter timestamp_unit based on the unit of time (Velodyne) or t (Ouster) field in PoindCloud2 rostopic
  4. Line number (we tested 16, 32 and 64 line, but not tested 128 or above): scan_line
  5. Translational extrinsic: extrinsic_T
  6. Rotational extrinsic: extrinsic_R (only support rotation matrix)
  • The extrinsic parameters in FAST-LIO is defined as the LiDAR's pose (position and rotation matrix) in IMU body frame (i.e. the IMU is the base frame).

Step B: Run below

    cd ~/$FAST_LIO_ROS_DIR$
    source devel/setup.bash
    roslaunch fast_lio mapping_velodyne.launch

Step C: Run LiDAR's ros driver or play rosbag.

3.4 PCD file save

Set pcd_save_enable in launchfile to 1. All the scans (in global frame) will be accumulated and saved to the file FAST_LIO/PCD/scans.pcd after the FAST-LIO is terminated. pcl_viewer scans.pcd can visualize the point clouds.

Tips for pcl_viewer:

  • change what to visualize/color by pressing keyboard 1,2,3,4,5 when pcl_viewer is running.
    1 is all random
    2 is X values
    3 is Y values
    4 is Z values
    5 is intensity

4. Rosbag Example

4.1 Livox Avia Rosbag

Files: Can be downloaded from google drive

Run:

roslaunch fast_lio mapping_avia.launch
rosbag play YOUR_DOWNLOADED.bag

4.2 Velodyne HDL-32E Rosbag

NCLT Dataset: Original bin file can be found here.

We produce Rosbag Files and a python script to generate Rosbag files: python3 sensordata_to_rosbag_fastlio.py bin_file_dir bag_name.bag

Run:

roslaunch fast_lio mapping_velodyne.launch
rosbag play YOUR_DOWNLOADED.bag

5.Implementation on UAV

In order to validate the robustness and computational efficiency of FAST-LIO in actual mobile robots, we build a small-scale quadrotor which can carry a Livox Avia LiDAR with 70 degree FoV and a DJI Manifold 2-C onboard computer with a 1.8 GHz Intel i7-8550U CPU and 8 G RAM, as shown in below.

The main structure of this UAV is 3d printed (Aluminum or PLA), the .stl file will be open-sourced in the future.

6.Acknowledgments

Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time), Livox_Mapping, LINS and Loam_Livox.

fast_lio's People

Contributors

borongyuan avatar ecstasy-ec avatar huguet57 avatar kennys99 avatar maoxiang1991 avatar matosinho avatar xw-hku avatar zang09 avatar zfc-zfc avatar ziv-lin avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

fast_lio's Issues

Large drift in generated map using Velodyne VLP 16

Hello,

Thanks for sharing such amazing work. I am using fastlio 2 for map generation using Velodyne vlp16 and intel l515 (for imu). For some scenarios, it is generating an amazing map. But for some, there is a large drift during mapping. Can you please help me if there is any fine-tuning needed for the same?

Snapshot (Scene: Car parking basement)
Screenshot from 2021-07-16 10-11-48

Adapt for use with a specific external IMU

Hi, so I would like to try this package, I've been having decent results with Ouster's built-in IMU but I wanna try it using a Microstrain IMU that I have. The problem is the sensor has different coordinates for acceleration and attitude so I'm not sure how to get all the transformations needed correctly in one matrix. Is there a way to adapt the code to have 2 separate ext matrices? Mine would look something like this:
extrinsicRot: [-1, 0, 0,
0, 1, 0,
0, 0, -1]
extrinsicRPY: [0, 1, 0,
-1, 0, 0,
0, 0, 1]
There should be a way to make this possible but I'm not exactly sure where to start as I am not yet familiar with FAST-LIO

里程计信息,

启动了mapping_avia.launch会发布里程计信息,我现在正在给机器狗做定位导航,机器狗没有编码器,所以需要利用雷达和imu得出里程计信息,请问有什么方法可以只发布里程计信息吗

Can it be used without IMU / IMU recomendations ?

Hello everyone, thanks for taking the time to answer.

Is it possible to run without IMU because my IMU is unreliable? Also, can somebody recommend any budget IMU ? Thanks in advance. My lidar is a VLP-16.

Question about the cpu consume

Hi,Dr Xu
Thank you for the amazing work,I have a problem about the program cpu.
my computer is Ubuntu16.04 : intel [email protected]*6,GeForce GTX 1660Ti/PCle/SSE2
I have a vlp16, and test the data I recorded use the mapping_velodyne.launch with the default parameters,
I find that, the data processing frequency is lower than 10Hz[Not real time] in the first few minutes, and the CPU usage is also high.
Is this normal?
2021-07-22 17-45-43屏幕截图

thanks.

PointCloud Intensity

Hi:

I'm using FAST-LIO with a Livox Horizon and everything is working well, but when I suscribe to /cloud_registered and save pcd files the intensity is always 0. Even in rviz I can't see the intensity.
How could I enable it?

Thanks in advance

Does Fast-lio-1.0 support MId-70?

HI:
Does Fast-lio-1.0 support MId-70?
if it supports, do you have turning good parameter for Mid-70? parameters is " edgea edgeb smallp_ratio point_filter_num ..."

#include <fast_lio/States.h> not present

I would like to buy an AVIA, but I tried to install your FAST_LIO package first, but once the ros_melodic - PCL OPENCV and eigen packages are installed, when I download your ghitub it gives me a privacy error I had to comment the line "### cmake_policy (SET CMP0074 NEW) "otherwise the compilation does not proceed and now I have the problem that gives me an error because you have not inserted in the [include] folder a library #include <fast_lio / States.h>, now you can correct the problem and insert all the right libraries? . Another thing seems that the vs ghitub must reside inside the src of the space where livox_ros_driver also resides otherwise if you put it in a different space at the time of catkin_make it does not find the ros_drive directory and the compilation stops. Can you explain better and be more precise in all the steps otherwise we will not be able to proceed, unfortunately we are not as expert programmers as you are? Thank you
this is the terminal error:
[ 64%] Building CXX object FAST_LIO/CMakeFiles/loam_laserMapping.dir/src/laserMapping.cpp.o
In file included from /home/livox2/ws_livox/src/FAST_LIO/src/laserMapping.cpp:47:0:
/home/livox2/ws_livox/src/FAST_LIO/include/common_lib.h:8:10: fatal error: fast_lio/States.h: File o directory non esistente
#include <fast_lio/States.h>
^~~~~~~~~~~~~~~~~~~
compilation terminated.
FAST_LIO/CMakeFiles/loam_laserMapping.dir/build.make:62: recipe for target 'FAST_LIO/CMakeFiles/loam_laserMapping.dir/src/laserMapping.cpp.o' failed
make[2]: *** [FAST_LIO/CMakeFiles/loam_laserMapping.dir/src/laserMapping.cpp.o] Error 1
CMakeFiles/Makefile2:3616: recipe for target 'FAST_LIO/CMakeFiles/loam_laserMapping.dir/all' failed
make[1]: *** [FAST_LIO/CMakeFiles/loam_laserMapping.dir/all] Error 2
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j1 -l1" failed
livox2@livox2-VirtualBox:~/ws_livox$

Ideal IMU Frequency and Time Synchronization

Hi,

Can you please suggest an ideal IMU frequency for this package? Plus, can you please comment on achieving better time synchronization between the IMU and Livox (Mid-70) Custom Messages ?

Thanks.

livox-ros-driver catkin make fsiled

[ 76%] Built target livox_ros_driver_generate_messages
[ 80%] Building CXX object livox_ros_driver/CMakeFiles/livox_ros_driver_node.dir/timesync/timesync.cpp.o
[ 84%] Building CXX object livox_ros_driver/CMakeFiles/livox_ros_driver_node.dir/timesync/user_uart/user_uart.cpp.o
[ 88%] Building CXX object livox_ros_driver/CMakeFiles/livox_ros_driver_node.dir/common/comm/comm_protocol.cpp.o
[ 92%] Building CXX object livox_ros_driver/CMakeFiles/livox_ros_driver_node.dir/common/comm/sdk_protocol.cpp.o
[ 96%] Building CXX object livox_ros_driver/CMakeFiles/livox_ros_driver_node.dir/common/comm/gps_protocol.cpp.o
[100%] Linking CXX executable /home/dji/ws_livox/devel/lib/livox_ros_driver/livox_ros_driver_node
CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function livox_ros::Lddc::CreateBagFile(std::string const&)': lddc.cpp:(.text+0x41b): undefined reference to rosbag::Bag::open(std::string const&, unsigned int)'
lddc.cpp:(.text+0x4ec): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)' CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function livox_ros::Lddc::PrepareExit()':
lddc.cpp:(.text+0x677): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)' lddc.cpp:(.text+0x6f0): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)'
CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function livox_ros::Lddc::GetCurrentPublisher(unsigned char)': lddc.cpp:(.text+0x13ca): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)'
lddc.cpp:(.text+0x1459): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)' CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o:lddc.cpp:(.text+0x1539): more undefined references to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)' follow
CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function livox_ros::Lddc::PublishPointcloud2(livox_ros::LidarDataQueue*, unsigned int, unsigned char)': lddc.cpp:(.text+0x2016): undefined reference to ros::Publisher::getTopic() const'
lddc.cpp:(.text+0x239c): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)' CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function livox_ros::Lddc::PublishPointcloudData(livox_ros::LidarDataQueue*, unsigned int, unsigned char)':
lddc.cpp:(.text+0x270e): undefined reference to ros::Publisher::getTopic() const' lddc.cpp:(.text+0x2ad7): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)'
CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function livox_ros::Lddc::PublishCustomPointcloud(livox_ros::LidarDataQueue*, unsigned int, unsigned char)': lddc.cpp:(.text+0x2fcb): undefined reference to ros::Publisher::getTopic() const'
lddc.cpp:(.text+0x312a): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)' CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function livox_ros::Lddc::PublishImuData(livox_ros::LidarDataQueue*, unsigned int, unsigned char)':
lddc.cpp:(.text+0x3574): undefined reference to ros::Publisher::getTopic() const' CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function void rosbag::Bag::writeMessageDataRecord<sensor_msgs::PointCloud2_<std::allocator > >(unsigned int, ros::Time const&, sensor_msgs::PointCloud2_<std::allocator > const&)':
lddc.cpp:(.text.ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs12PointCloud2_ISaIvEEEEEvjRKN3ros4TimeERKT[ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs12PointCloud2_ISaIvEEEEEvjRKN3ros4TimeERKT]+0x104): undefined reference to rosbag::Bag::toHeaderString(ros::Time const*) const' lddc.cpp:(.text._ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs12PointCloud2_ISaIvEEEEEvjRKN3ros4TimeERKT_[_ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs12PointCloud2_ISaIvEEEEEvjRKN3ros4TimeERKT_]+0x246): undefined reference to rosbag::Bag::writeHeader(std::map<std::string, std::string, std::lessstd::string, std::allocator<std::pair<std::string const, std::string> > > const&)'
lddc.cpp:(.text.ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs12PointCloud2_ISaIvEEEEEvjRKN3ros4TimeERKT[ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs12PointCloud2_ISaIvEEEEEvjRKN3ros4TimeERKT]+0x280): undefined reference to rosbag::Bag::appendHeaderToBuffer(rosbag::Buffer&, std::map<std::string, std::string, std::less<std::string>, std::allocator<std::pair<std::string const, std::string> > > const&)' CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function void rosbag::Bag::writeMessageDataRecord<pcl::PointCloudpcl::PointXYZI >(unsigned int, ros::Time const&, pcl::PointCloudpcl::PointXYZI const&)':
lddc.cpp:(.text.ZN6rosbag3Bag22writeMessageDataRecordIN3pcl10PointCloudINS2_9PointXYZIEEEEEvjRKN3ros4TimeERKT[ZN6rosbag3Bag22writeMessageDataRecordIN3pcl10PointCloudINS2_9PointXYZIEEEEEvjRKN3ros4TimeERKT]+0x104): undefined reference to rosbag::Bag::toHeaderString(ros::Time const*) const' lddc.cpp:(.text._ZN6rosbag3Bag22writeMessageDataRecordIN3pcl10PointCloudINS2_9PointXYZIEEEEEvjRKN3ros4TimeERKT_[_ZN6rosbag3Bag22writeMessageDataRecordIN3pcl10PointCloudINS2_9PointXYZIEEEEEvjRKN3ros4TimeERKT_]+0x2a1): undefined reference to rosbag::Bag::writeHeader(std::map<std::string, std::string, std::lessstd::string, std::allocator<std::pair<std::string const, std::string> > > const&)'
lddc.cpp:(.text.ZN6rosbag3Bag22writeMessageDataRecordIN3pcl10PointCloudINS2_9PointXYZIEEEEEvjRKN3ros4TimeERKT[ZN6rosbag3Bag22writeMessageDataRecordIN3pcl10PointCloudINS2_9PointXYZIEEEEEvjRKN3ros4TimeERKT]+0x2d9): undefined reference to rosbag::Bag::appendHeaderToBuffer(rosbag::Buffer&, std::map<std::string, std::string, std::less<std::string>, std::allocator<std::pair<std::string const, std::string> > > const&)' CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function void rosbag::Bag::writeMessageDataRecord<livox_ros_driver::CustomMsg_<std::allocator > >(unsigned int, ros::Time const&, livox_ros_driver::CustomMsg_<std::allocator > const&)':
lddc.cpp:(.text.ZN6rosbag3Bag22writeMessageDataRecordIN16livox_ros_driver10CustomMsg_ISaIvEEEEEvjRKN3ros4TimeERKT[ZN6rosbag3Bag22writeMessageDataRecordIN16livox_ros_driver10CustomMsg_ISaIvEEEEEvjRKN3ros4TimeERKT]+0x104): undefined reference to rosbag::Bag::toHeaderString(ros::Time const*) const' lddc.cpp:(.text._ZN6rosbag3Bag22writeMessageDataRecordIN16livox_ros_driver10CustomMsg_ISaIvEEEEEvjRKN3ros4TimeERKT_[_ZN6rosbag3Bag22writeMessageDataRecordIN16livox_ros_driver10CustomMsg_ISaIvEEEEEvjRKN3ros4TimeERKT_]+0x243): undefined reference to rosbag::Bag::writeHeader(std::map<std::string, std::string, std::lessstd::string, std::allocator<std::pair<std::string const, std::string> > > const&)'
lddc.cpp:(.text.ZN6rosbag3Bag22writeMessageDataRecordIN16livox_ros_driver10CustomMsg_ISaIvEEEEEvjRKN3ros4TimeERKT[ZN6rosbag3Bag22writeMessageDataRecordIN16livox_ros_driver10CustomMsg_ISaIvEEEEEvjRKN3ros4TimeERKT]+0x27d): undefined reference to rosbag::Bag::appendHeaderToBuffer(rosbag::Buffer&, std::map<std::string, std::string, std::less<std::string>, std::allocator<std::pair<std::string const, std::string> > > const&)' CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/lddc.cpp.o: In function void rosbag::Bag::writeMessageDataRecord<sensor_msgs::Imu_<std::allocator > >(unsigned int, ros::Time const&, sensor_msgs::Imu_<std::allocator > const&)':
lddc.cpp:(.text.ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs4Imu_ISaIvEEEEEvjRKN3ros4TimeERKT[ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs4Imu_ISaIvEEEEEvjRKN3ros4TimeERKT]+0x104): undefined reference to rosbag::Bag::toHeaderString(ros::Time const*) const' lddc.cpp:(.text._ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs4Imu_ISaIvEEEEEvjRKN3ros4TimeERKT_[_ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs4Imu_ISaIvEEEEEvjRKN3ros4TimeERKT_]+0x21b): undefined reference to rosbag::Bag::writeHeader(std::map<std::string, std::string, std::lessstd::string, std::allocator<std::pair<std::string const, std::string> > > const&)'
lddc.cpp:(.text.ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs4Imu_ISaIvEEEEEvjRKN3ros4TimeERKT[ZN6rosbag3Bag22writeMessageDataRecordIN11sensor_msgs4Imu_ISaIvEEEEEvjRKN3ros4TimeERKT]+0x253): undefined reference to rosbag::Bag::appendHeaderToBuffer(rosbag::Buffer&, std::map<std::string, std::string, std::less<std::string>, std::allocator<std::pair<std::string const, std::string> > > const&)' CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/livox_ros_driver.cpp.o: In function main':
livox_ros_driver.cpp:(.text.startup+0x40): undefined reference to ros::console::set_logger_level(std::string const&, ros::console::levels::Level)' livox_ros_driver.cpp:(.text.startup+0x8c): undefined reference to ros::init(int&, char**, std::string const&, unsigned int)'
livox_ros_driver.cpp:(.text.startup+0xf8): undefined reference to ros::NodeHandle::NodeHandle(std::string const&, std::map<std::string, std::string, std::less<std::string>, std::allocator<std::pair<std::string const, std::string> > > const&)' livox_ros_driver.cpp:(.text.startup+0x208): undefined reference to ros::NodeHandle::getParam(std::string const&, int&) const'
livox_ros_driver.cpp:(.text.startup+0x246): undefined reference to ros::NodeHandle::getParam(std::string const&, int&) const' livox_ros_driver.cpp:(.text.startup+0x287): undefined reference to ros::NodeHandle::getParam(std::string const&, int&) const'
livox_ros_driver.cpp:(.text.startup+0x2c8): undefined reference to ros::NodeHandle::getParam(std::string const&, double&) const' livox_ros_driver.cpp:(.text.startup+0x309): undefined reference to ros::NodeHandle::getParam(std::string const&, int&) const'
livox_ros_driver.cpp:(.text.startup+0x345): undefined reference to ros::NodeHandle::getParam(std::string const&, std::string&) const' livox_ros_driver.cpp:(.text.startup+0x383): undefined reference to ros::NodeHandle::getParam(std::string const&, bool&) const'
livox_ros_driver.cpp:(.text.startup+0x3c1): undefined reference to ros::NodeHandle::getParam(std::string const&, bool&) const' livox_ros_driver.cpp:(.text.startup+0x4c9): undefined reference to ros::NodeHandle::getParam(std::string const&, std::string&) const'
livox_ros_driver.cpp:(.text.startup+0x558): undefined reference to ros::NodeHandle::getParam(std::string const&, std::string&) const' livox_ros_driver.cpp:(.text.startup+0x73e): undefined reference to ros::NodeHandle::getParam(std::string const&, std::string&) const'
livox_ros_driver.cpp:(.text.startup+0x929): undefined reference to ros::NodeHandle::getParam(std::string const&, std::string&) const' livox_ros_driver.cpp:(.text.startup+0x9b8): undefined reference to ros::NodeHandle::getParam(std::string const&, std::string&) const'
livox_ros_driver.cpp:(.text.startup+0xdb5): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)' livox_ros_driver.cpp:(.text.startup+0xe9c): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)'
livox_ros_driver.cpp:(.text.startup+0xf9c): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)' livox_ros_driver.cpp:(.text.startup+0x10d5): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)'
livox_ros_driver.cpp:(.text.startup+0x1178): undefined reference to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)' CMakeFiles/livox_ros_driver_node.dir/livox_ros_driver/livox_ros_driver.cpp.o:livox_ros_driver.cpp:(.text.startup+0x126b): more undefined references to ros::console::initializeLogLocation(ros::console::LogLocation*, std::string const&, ros::console::levels::Level)' follow
collect2: error: ld returned 1 exit status
livox_ros_driver/CMakeFiles/livox_ros_driver_node.dir/build.make:1074: recipe for target '/home/dji/ws_livox/devel/lib/livox_ros_driver/livox_ros_driver_node' failed
make[2]: *** [/home/dji/ws_livox/devel/lib/livox_ros_driver/livox_ros_driver_node] Error 1
CMakeFiles/Makefile2:1012: recipe for target 'livox_ros_driver/CMakeFiles/livox_ros_driver_node.dir/all' failed
make[1]: *** [livox_ros_driver/CMakeFiles/livox_ros_driver_node.dir/all] Error 2
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j8 -l8" failed

[ INFO] [1625547852.411847770]: IMU Initializing: 5.0 %

[ INFO] [1625547852.411847770]: IMU Initializing: 5.0 %
[ WARN] [1625547852.415338028]: Reset ImuProcess
[ INFO] [1625547852.415483487]: IMU Initials: Gravity: 0.5451 0.0623 -9.7936 0.9901; state.bias_g: 0.0001 0.0001 0.0001; acc covarience: 0.10000000 0.10000000 0.10000000; gry covarience: 0.10000000 0.10000000 0.10000000
FAST-LIO not ready

IMU Initializing: 5.0 %?
FAST-LIO not ready

Rviz configuration

Hello, I would like to ask you how the topic was configured in the fixed frame and pointclouds in RVIZ when you made the drawing. I did not find the poingcloud data
thank you for your answer

Odometry Drifted with error Integer indices would overflow

Hi,

When I tested this package with Mid70 Lidar, I got the following error:

Leaf size is too small for the input dataset. Integer indices would overflow.[pcl::VoxelGrid::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.

Then, the published odometry would drift to very far distance. Is this normal?

Thanks.

Time Synchronization

Hi @XW-HKU
"Please make sure the IMU and LiDAR are Synchronized, that's important."


Does it mean to ensure that the time source between LiDAR and IMU is the same?

Long build times for loam_mapping/loam_feature_extract

Thank you for that awesome project!

I am experiencing quite long build times for building the project myself within my ros working directory. It takes about 2 minutes at one step. This, of course, would be totally fine if it would just happen ones. However, this happens on any changes that I do to the code with a following build. Like this it is really cumbersome to further code on your project.

Do you also experience this long build times when doing any changes? How do you go about that? Is there any possibility to speed things up? I could not really find out which part is causing this long delay since catkin_make VERBOSE=1 does not give much more info on that build step.

The actual build step that needs to happen on any code manipulation and that takes rougly 2 minutes:

[ 97%] Built target loam_feat_extract
/* at here it takes about 2 minutes until the [100%] apperas */
[100%] Linking CXX executable /home/me/catkin_ws/devel/lib/fast_lio/loam_laserMapping

Real-time performance

Hey, I noticed in FAST-LIO sometimes when I play a ROS bag with normal speed, the bag finished playing and everything is okay, but it takes FAST-LIO more time and it keeps processing the data even after the bag finishes playing, is this normal behaviour?

Use for long continuous SLAM

Hey, thank you again for the amazing work that you guys have put in! I have a couple of questions about performance and optimization of the algorithm during longer periods of scanning. I noticed that my RAM usage goes up higher and higher each second the map is being populated, and after a while I suppose it would overflow and crash the program ( I have 32GB on my machine so it would take a few minutes but still), is there any way to stop this or at least clear some of the scans after a certain time so we can free some RAM? I'm guessing this is mainly due to RViz as well using a lot to visualize the whole map with that many points (my lidar has 128 channels so I get around 2mil points per second), which is my second question as well. I'm trying to think of a way to visualize some sparser version of the map in rviz on the screen so I can save on PC resources but I would still like the end result in the pcd to be with the same quality as if I had publish_dense set to 1 with all the points, possibly one solutions that comes to my mind is having a separate topic that is more filtered and less dense just for visualization in rviz? Let me know if you have suggestions, thanks!

Pose largely drift

Hi, @XW-HKU

I compiled Fast-LIO in ubuntu16.04 and I tried to test it with Avia. But the result may be totally wrong, I'm curious about what I may have done to make this kind of strange phenomenon?

2020-12-12 11-33-33

The pose may drift even thought it is still.

Looking forward to your help ;>

无人机设计图

您的工作真的太棒了
我在您的代码的基础上做了一点儿微小的工作,增加了GNSS校准功能,在大场景之下提高了鲁棒性,在进行评估之后会找您进行代码合并。
请问您有这个小型无人机的设计图纸和零件的购买链接么,我也想在进行UAV SLAM验证(ps.horizon特别适合放在无人机上,所以请问第二版什么时候上线哈哈哈

这个是我的一些效果:
截屏2021-05-28 下午6 43 11

2021-06-06.01.11.32.mp4

How to compute H ???

Dear friend:
我直接说中文啦!我是个slam初学者,看了您们的论文“FAST-LIO: A Fast, Robust LiDAR-inertial Odometry Package by Tightly-Coupled Iterated Kalman Filter”,有个地方很迷惑,,不知道论文公式14中雅可比H怎么计算的?具体什么形式呢?
img

/*** calculate the Measuremnt Jacobian matrix H ***/ Eigen::Vector3d A(point_crossmat * state.rot_end.transpose() * norm_vec); Hsub.row(i) << VEC_FROM_ARRAY(A), norm_p.x, norm_p.y, norm_p.z;

Online Georeference

Hi!

This is not an issue with the library, more of a general question. Could you suggest how I would integrate GPS for online georeferencing?

Ideally there would be a transform for the point cloud that is in UTM coordinates.

Any help would be appreciated.

Point-to-edge/corner cost in the code and in the paper

The FAST-LIO described in your paper uses both planar/surf/flat features and edge/corner/sharp features for state estimation.

In your implementation, the feature processing part extracts and publishes both flat and sharp features src/feature_extract.cpp#L127#L128. But in state estimation part, it seems that only flat features are subscribed and used src/laserMapping.cpp#L627.

May I ask why the sharp features are not used in the implementation?

地图的保存

我用这个算法构建了一个非常满意的地方, 可是应该用什么方法保存下来用来定位导航呢?

Postprocess optimization

Dear XW-HKU:

I use to have a low cpu consuming yaml file for data capture (recording a bag file) and a highly optimized for accuracy yaml file for postprocessing the bag recorded in field.
My question, regarding this, is:

  • point_filter_num: I understand that this downsamples the pointcloud, grouping the number of points indicated in the parameter. Is it right? If I want the best result should I use value 1?
  • max_iteration: this referes to the maximum iterations on ICP adjustment per scan. Is it right? So I should use around 10?
  • filter_size_surf: This I think that is the voxelization size. So 0.5 means that every plane of 0.5x0.5 should be used in the adjustment. Is it right?
  • filter_size_map: This value I have no idea what means.

If I want the best fitting, even playing the bag at rate 0.5 or 0.1:

  • What parameters do you recomend for the best accuracy?
  • Should I modify any of the ones hardcoded in the sources?

Thanks in advance

RViz performance

Hello, thank you again for this amazing project, I've been seeing pretty good results using it so far. One small issue I've had is in RViz when visualizing the data, I usually get 3-10 fps only and it works slowly even though the map looks great, I think it's just a bit too many points for my machine to handle. I'm running on an NVidia Jetson Xavier with an OS1-128, any suggestions about maybe somehow reducing the number of points RViz visualizes so I can improve performance a bit?

Integration with GNSS

First of all, thanks for the great work & research you've done on SLAM, this is definitely the best implementation so far what comes to mapping precision and performance!

I have a GNSS receiver which outputs centimeter accurate position information at 8 Hz synced with lidar & imu clock, and I'd like to try to improve the long-run odometry drift by fusing GNSS location.

What would be the best approach to do that? Is it possible to enter external position estimate from GNSS to Kalman filter?

Optimally, I'd want to fuse GNSS location when it's available (outdoors, with proper GNSS fix) up to 8 Hz. But when it's indoors or with poor GNSS reception, I'd use the existing prediction system.

Also, what would be the best way to alter the initial rotation (heading/yaw) so that it would match the north-referenced XYZ coordinates from GNSS?

Any help would be highly appreciated!

Horizon

<arg name="rviz" default="true" />

<rosparam command="load" file="$(find fast_lio)/config/horizon.yaml" />

<param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="3"/>
<param name="max_iteration" type="int" value="3" />
<param name="scan_publish_enable" type="bool" value="0" />
<param name="dense_publish_enable" type="bool" value="1" />
<param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log_enable" type="bool" value="1" />
<param name="pcd_save_enable" type="bool" value="1" />
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen"  /> 

<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio)/rviz_cfg/loam_livox.rviz" />
</group>
but pcd file has not issues!

livox-horizon测试

目前的1.0程序版本可以驱动livox-horizon,但是由于垂直视场太小,(horizon 是25°),所以在闭环检查时,问题就表现得比较严重,平面误差近20米,高程误差近2米。(大概介绍一下,我采集得情况,是个地下车库,采集不足10分钟,rosbag 11.7G),附上采用rosbag回放

imu.txt in empty

dji@dji-B85MG:/catkin_ws/src/FAST_LIO/Log$ python plot.py
plot.py:37: UserWarning: loadtxt: Empty input file: "imu.txt"
imu=np.loadtxt('imu.txt')
Traceback (most recent call last):
File "plot.py", line 38, in
time=imu[:,0]
IndexError: too many indices for array
dji@dji-B85MG:
/catkin_ws/src/FAST_LIO/Log$ python3 plot.py
Traceback (most recent call last):
File "plot.py", line 25, in
axs[j%4, j/4].plot(time, a_pre[:,i+j*3],'.-', label=lab_pre[i])
IndexError: only integers, slices (:), ellipsis (...), numpy.newaxis (None) and integer or boolean arrays are valid indices
dji@dji-B85MG:~/catkin_ws/src/FAST_LIO/Log$ code ..

livox mid rosbag support

the mid-70 1000 rosbag can be used in livox_mapping and livox_loam.

but in Fast_LIO, after rosbag play XXX.bag, a md5sum error will be show, (the bag will play anyway), and no pointclouds in rviz.

MID-40/70 with IMU

尊敬的港大团队好:

因为avia型号买不到,只能尝试用mid-40和70绑定外接imu,遇到些困难,请指点下~

  • 尝试把loam_livox里,mid系列的launch_file 拿到fast_lio尝试。可以看到点云,但优化可能不明显。
    您会考虑 mid系列外接imu 的优化么?

  • 还试了按过去的相关回复修改,但mid系列的点云没有出现在rviz界面里。请问还适用么?

相关回复:`Does Fast-lio-1.0 support MId-70?` 
FAST LIO可以外接IMU(修改laser_mapping.cpp里面的ros 订阅topic name),
不过需要保证旋转上没有偏差,也就是rotation的外参是单位阵。
平移外参可以直接在common_lib.h里面修改。

A question about formula 18?

您好:
我在读您的论文的时候,关于论文中的公式18有点不太懂,这个公式似乎和一般的IEKF更新不太一样?请问在哪里能找到相关的资料或文献说明呢?非常感谢您的解答!
WXWorkCapture_1627459168787

FastLio-2: catkin_make & ikd-Tree Failed (因ikd-Tree编码失败?)

尊敬的港大团队好:

先恭喜恭喜,新作品的进展让人激动。

这次尝试编译Fast Lio2遇到困难, 请多多指教 😀:

0. 安装

在说明文稿 “2.build” 里的git clone https://github.com/XW-HKU/fast_lio.git,
可能要改为:git clone https://github.com/hku-mars/FAST_LIO.git

1. 第一次编译,不论是用终端clone,还是直接下载都没有Ikd-treed文件夹内的文件,导致编译失败。可能是文件夹名存在@符号造成的?

简化的报错信息如下

make[2]: *** 没有规则可制作目标“
~  /ikd-Tree/ikd_Tree.cpp”,

fatal error: ikd-Tree/ikd_Tree.h: 
没有那个文件或目录 #include <ikd-Tree/ikd_Tree.h>

2. 再次尝试编译, 把Ikd-treed的档案手动copy到文件夹,CMD输入catkin_make有大量的报错。怀疑是编码问题 或 cmake版本问题,多多指教啊~

报错档案如下, 共三类。

  • 第一类是编码报错

简化的报错信息如下

[ 29%] Building CXX object FAST_LIO/ ... /ikd_Tree.cpp.o

~ ikd-Tree/ikd_Tree.cpp:70:76: 

error: stray ‘\302’ in program
   <title>ikd-Tree/ikd_Tree.cpp at 3d115a41377243420a74fc15dd7cf7ef337730df 
�� hku-mars/ikd-Tree · GitHub</title>
  • 第二类是语法报错

简化的报错信息如下

~ ikd_Tree.cpp:320:12: 

warning: missing terminating ' character
       <!-- '"` --><!-- </textarea></xmp> --></option></form><form class="js-site-search-form" role="search" aria-label="Site" data-scope-type="Repository" data-scope-id="341097199" data-scoped-search-url="/hku-mars/ikd-Tree/search" data-owner-scoped-search-url="/orgs/hku-mars/search" data-unscoped-search-url="/search" action="/hku-mars/ikd-Tree/search" accept-charset="UTF-8" method="get">
  • 第三类似乎是建议改写

简化的报错信息如下

~ /laserMapping.cpp:859:82: 
error: ‘kdtree_incremental_time’ was not declared in this scope
                 
aver_time_incre = 
aver_time_incre * (frame_num - 1)/frame_num + (kdtree_incremental_time)/frame_num;

------------------------------------------
~/laserMapping.cpp:859:82: 

note: suggested alternative: ‘map_incremental’
                
 aver_time_incre = 
aver_time_incre * (frame_num - 1)/frame_num + (kdtree_incremental_time)/frame_num;
                                                                                 

Does Current Version support the VLP16?

Thanks for your excellent work! I notice that in the feature_extract.cpp, there is a lidar type selection among vlp16, horizon... So for the current version, can we run the vlp-16 + imu dataset with adjusting some parameters?

Point cloud is abnormal with direct method

Hi, thank you for sharing this great job!
I use a velodyne VLP-32C lidar with external imu. For a outdoor data, if I set extract feature to true, the program runs well, but has small drift in z axis. Then I set extract feature to false, the trajectory is still right, but the pointcloud in rviz is abnormal. The points far from ground are lost, I mean, only the base of a building is remain, points about 2 meters high are gone.
capture1
capture2
The first image is with extract feature on, and second is off.
Is this a normal phenomenon?

Point stored in sensor position

Dear Cris:

When I use point_filter_num=1 and I store the PCD I get a point in the position of the sensor on all of the scans.
Is there a reason for that?
I mean, if I record the raw lidar from the sensor there is not a point in the coords 0,0,0, of the scan.

Thanks

Question about discrete model in fast lio

Thanks for your great job! I test fast lio2 on KITTI dataset and get nice results.
But I have a question about discrete model when I read fast lio paper.
image
According to formula (2) (3), we can get P_{t+1} = P_{t} + V_{t} * δt , why not P_{t+1} = P_{t} + V_{t} * δt + 1/2 * a_{t} * δt^{2}?

Support for L515

Hey, do you guys have any pointers on how to integrate L515 with FAST_LIO

I've seen

void Preprocess::process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out)
{
switch (lidar_type)
{
case OUST64:
oust64_handler(msg);
break;
case VELO16:
velodyne_handler(msg);
break;
default:
printf("Error LiDAR Type");
break;
}
*pcl_out = pl_surf;
}

And also seen the specific handers for each lidar, but i am not able to figure out how to write a l515_handler, in specific i can't figure out the processing function to convert the PCL data from L515 into PointCloudXYZI format.

save trajectory from scan

Hi, is there a way currently to save the trajectory from a scan in something like a pcd file like the map is saved?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.