Code Monkey home page Code Monkey logo

camlasercalibratool's Introduction

Camera Laser Calibration Tool

Build Status

标定相关的理论推导以及拓展知识请阅读知乎专栏文章:https://zhuanlan.zhihu.com/p/137501892

1. 介绍

这是一个基于 ROS 的单线激光和相机外参数自动标定代码。标定原理如下图所示,相机通过二维码估计标定板平面在相机坐标系下的平面方程,由于激光点云落在平面上,将点云通过激光坐标系到相机坐标系的外参数 $ T_{cl} $ 转换到相机坐标系,构建点到平面的距离作为误差,使用非线性最小二乘进行求解。 lasercamcal

2. 特征

  1. 支持多 April tag 格式。 可以选择多 apriltag 的标定板 ( kalibr_tag.pdf ) 或者自己打印一个 apriltag 做标定板(apriltag.pdf)。
  2. 支持多种相机模型radial-tangential (radtan) : (distortion_coeffs: [k1 k2 r1 r2]); equidistant (equi):distortion_coeffs: [k1 k2 k3 k4]). More info please visit kalibr website.
  3. 激光线自动检测,无须手标。会自动提取激光线中落在标定板上的激光点,前提是标定板在激光正前方 120 度范围内,并且激光前方 2m 范围内只会存在一个连续的直线线段,所以请你在空旷的地方采集数据,不然激光数据会提取错误。
  4. 利用标定板的边界约束,标定结果更加准确。这个是隐藏的功能,暂时未对外开放接口,需要你修改代码。

3. 编译方法

mkdir LaserCameraCal_ws
mkdir ../src
cd src
git clone https://github.com/MegviiRobot/CamLaserCalibraTool
cd ..
catkin_make -DCMAKE_BUILD_TYPE=Release

4. 运行

4.1 仿真数据

**强烈建议: **先用仿真数据试试这个标定系统,系统的可观性问题在仿真代码里都能找到验证,这样就能指导你如何采集数据。

cd LaserCameraCal_ws
source devel/setup.bash 
rosrun lasercamcal_ros simulation_lasercamcal_node

特别地,请仔细阅读 main/calibr_simulation.cpp ,修改数据的生成观察系统的可观性。

4.2 实际数据,运行前的准备

请配置好 config/calibra_config.yaml 文件,里面有相机模型参数,rosbag 数据包的名字和保存路径,相机模型以及标定板的尺寸和类型等等。 具体请参考对应的 config.yaml。

采集激光数据制作 rosbag,请将标定板放于激光和相机前方 0.3m ~ 1.5m 左右,充分运动标定板(各个轴,各个角度,各个距离都充分运动)。datacollect

4.3 先运行 kalibr 检测图像二维码

会把相机和标定板之间的姿态保存成一个 txt,用于后续标定。

cd LaserCameraCal_ws
source devel/setup.bash
roslaunch lasercamcal_ros kalibra_apriltag.launch 

4.4 再运行激光视觉外参数标定代码

会自动检测激光在标定板上的线段,并完成标定和保存结果。

roslaunch lasercamcal_ros calibra_offline.launch 

激光线条的自动获取如下图所示,其中红色部分为激光检测到的标定板线段,请注意保持激光前方是空旷区域:

detect

4.5 验证结果

roslaunch lasercamcal_ros debug.launch 
rosbag play data.bag

运行 debug 工具,看激光光条和图像是否对齐的比较好。 calibra

5. TODO

  1. 支持修改相机采样间隔??? 还是说采用自动判断信息熵?

6. Authors

  1. Yijia He, if you have any question, please contact heyijia_2013 at 163 dot com
  2. XiZhen Xiao
  3. Xiao Liu, his homepage

7. Ref:

2004, Qilong Zhang, Extrinsic Calibration of a Camera and Laser Range Finder (improves camera calibration).

camlasercalibratool's People

Contributors

heyijia 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

camlasercalibratool's Issues

A question about tag info

Hi,您好,我是第一次接触相机标定相关的领域
目前在看你们程式码的时候有个部份看不太明白
想问一下,如过我是用doc/april_6x6_80x80cm_A0.pdf印出来当做标定板

  1. 在calibra_config_pinhole.yaml里,tag_type我该选kalibr_tag还是apriltag

  2. 关于tag_size的部份,我在kalibr的说明里看到这个标定板的tag_size应该是0.088,为什么你们的是0.165

# tag info
tag_type: 2 # 1: kalibr_tag, 2: apriltag
tag_size: 0.165 # tag size, unit meter
tag_spacing: 0.3 # tag spacing, only used in kalibr_tag. For details, please see kalibr tag description.
black_border: 1 # if you use kalibr_tag black_boarder = 2; if you use apriltag black_boarder = 1

how to set the parameters

Hi,
the file CamLaserCalibraTool/src/LaseCamCalCeres.cpp :
Eigen::Vector3d orig(0.0265+0.0165,0.0265+0.0165,0);
Eigen::Vector3d p1m( 0, 0, 0);
Eigen::Vector3d p2m( 0.5, 0, 0);
Eigen::Vector3d p3m( 0., 0.5, 0);
how the set the parameters about kalibr_tag

二维激光和相机位姿的求解

看到知乎上的二维激光和相机位姿的求解的求解方法。列出了几种方法
(1)计算带约束的最小化 Frobenius norm 问题来估计 R_lc
(2)文献(2)和(3)的求解闭式解法
(3)文献(4)的求解闭式解法

请问下,该代码中使用的是哪种方法求解?

Omni相机参数设置问题

您好,想请问下,我用Kalib按照Omni相机模型标定的鱼眼内参,但我看您的代码里没有对应的畸变参数(k1,k2,r1,r2),而是poly[]和inv_poly[],想请问下,这些参数如何对应的呢,或者能否提供下代码实现中的参考文献呢,谢谢!

关于标定板的尺寸

您好:
请问标定板的尺寸是越大越好吗?打印的标定板必须保证有1:1吗?

One D laser calibration

What do you think would happen if this calibration method was used on a 1D laser range finder and camera?

So that each observation contains the pose of the calibration pattern, as well as a single vector (0, 0, d) from the single range finder.

The PointInPlaneFactor still applies to this case.

代码理解

在计算相机姿态的时候,这句代码不是很理解:
const double tag_spacing_sz = tag_sz * (1.+tag_spacing); // 0.055 + 0.0165
tag_sz+tag_spacing可以理解,tag_sz+tag_sz*tag_spacing该怎么理解呢?
多谢。

怎么确定激光提取的直线端点对应在相机光心与板子边缘连线平面的? 这个需要实际的物理保证吗?

确定的光心平面。
https://github.com/MegviiRobot/CamLaserCalibraTool/blob/master/src/LaseCamCalCeres.cpp#L275

@HeYijia 我这边看代码,实际操作中,有点疑问。 怎么确定激光端点对应在相机光心与板子边缘连线平面的? 这个需要实际的物理保证吗?
https://github.com/MegviiRobot/CamLaserCalibraTool/blob/master/src/LaseCamCalCeres.cpp#L281

板子参数不一致,激光高度不一致,会存在 激光端点 不落在相机光心与板子边缘连线平面的问题吗?
Eigen::Vector3d orig(0.0265+0.0165,0.0265+0.0165,0);
Eigen::Vector3d p1m( 0, 0, 0);
Eigen::Vector3d p2m( 0.5, 0, 0);
Eigen::Vector3d p3m( 0., 0.5, 0);

Questions on apriltag detection and the projection parameters in yaml file

您好,很感谢开源您的标定代码,我在标定时候遇到了两个问题想请问下您

  1. 做apriltag标定的时候发现显示的frame很奇怪,和readme中给出的例子有比较大的区别,想请问下如何调整呢?我在运行roslaunch lasercamcal_ros calibra_offline.launch 时候的结果:
    ezgif com-video-to-gif

  2. yaml文件中的两个参数想请问下 camera_name 和下面projection_parameters应该怎么给呢?

谢谢

#camera calibration
model_type: KANNALA_BRANDT
camera_name: cam0
image_width: 2048
image_height: 1536

projection_parameters:
mu: 367.049931000148
mv: 366.94446918887405
u0: 368.7202381120387
v0: 241.13814795878562
k2: -0.02276964
k3: -0.00056958
k4: -0.0026224
k5: 0.00017455

(p.s. 另外谢谢您的博客 看着您和高博的博客入门的哈)

Erroneuous results

Hello,

The results i am getting make no physical sense considering my setup.

I was careful in providing the intrinsic parameters of the camera, and in insuring that the correct laser line was being extracted by 'AutoGetLinePts'.

Would it be possible to check my bag file and provide me with your feedback?

boundary plane constraint

想再请问下关于标定板尺寸约束的几个参数具体的含义.orig 是标定板坐标系在标定板左下角的坐标吗 (标定板坐标系就是图片中显示的frame?) p1m标定板左下角 p2m 右下角 p3m坐上角 请问是这样吗? 谢谢
image

Valid Calibra Data Less

Hi, 我标定时执行roslaunch lasercamecal_ros calibra_offline.launch 后,没几秒就结束了,打印出的消息有 Load apriltag pose size 46 Valid Calibra Data Less 请问是有效的数据点太少导致的嘛?我用的标定板是A4的,是不是因为标定板太小了?

PoseLocalParameterization中四元数更新代码错误?

在pose_local_parameterization.cpp的deltaQ函数中:

Eigen::Quaterniond deltaQ(const Eigen::Vector3d &theta) { Eigen::Quaterniond dq; Eigen::Vector3d half_theta = theta; // theta: so(3) 旋转向量 half_theta /= static_cast<double>(2.0); // half_theta: 四元数向量部分 dq.w() = static_cast<double>(1.0); dq.x() = half_theta.x(); dq.y() = half_theta.y(); dq.z() = half_theta.z(); return dq; // q增量 }
看了一些博客,了解到其中theta/2对应纯虚四元数向量,应该经过指数变换得到对应的四元数dq。但这里,直接将实部w赋值为1,未进行指数变换。

哪位大神可以指导一下?

参考:https://blog.csdn.net/hzwwpgmwy/article/details/86490556

使用MEI模型(catacamera),结果错误

在使用MEI模型的时候,计算相机的位置,(目测大概准确)
然后在show_node的时候,看到激光和我移动的方向,呈现一个镜像,看起来应该在关于垂直线翻转一下.
image
之后发现代码中假定了,摄像头出现了镜像.而我的摄像头没有镜像.
但是结果仍然不对,没有出现在标定板上的正确位置.

目前查看源代码时候发现.MEI相机模型在catacamera.
我使用的是opencv_contrib的omndir标定的内参.
但是omnidir有一个争议https://github.com/opencv/opencv_contrib/issues/1612
.

在这里对omnidir的函数简单梳理下,cv2.omnidir.undistortImage 和cv2.omnidir.projectPoints和cv2.omnidir.calibrate是一致的,和cv2.omnidir.undistortPoints不一致的.不一致在cv2.omnidir.undistortPoints最后返回的点,映射了一下.点,https://github.com/opencv/opencv_contrib/blob/1311b057475664b6af118fd1a405888bad4fd839/modules/ccalib/src/omnidir.cpp#L318

但是我在查看catacamera中代码时候,点也进行了映射.不知道是不是这个差异导致结果不对?

如果有懂的朋友麻烦解答下

About camera model

您好 选择pinhole模型在运行kalibra_apriltag卡在下面的地方 想请问下是不是哪里参数没给对呢
image
我的yaml文件是 (我用的是readme中同样的标定板)

scan_topic_name: "/scan"
img_topic_name: "/camera/image_raw"

# tag info
tag_type: 1 # 1: kalibr_tag, 2: apriltag
tag_size: 0.0451 # tag size, unit meter
tag_spacing: 0.3 # tag spacing, only used in kalibr_tag. For details, please see kalibr tag description.
black_border: 2 # if you use kalibr_tag black_boarder = 2; if you use apriltag black_boarder = 1

#camera calibration 
model_type: PINHOLE
camera_name: camera
image_width: 2048
image_height: 1536

distortion_parameters:
   k1: -0.39561955371546687
   k2: 0.14301415731672948
   p1: -0.00091786036772837
   p2: -0.0011805174547034807

projection_parameters:
   fx: 1115.3458479831127
   fy: 1115.5680569978117
   cx: 1047.8994454164401
   cy: 775.5928959466218

另外还想请问下样例中的KANNALA_BRANDT对应kalib中的什么模型呢?

最后还想问下哈 对于鱼眼镜头 哪种模型更适合呢?

谢谢哈 :)

catkin_make 错误

我在catkin_make的时候,出现了没有cere的问题.
然后我安装cere按照 http://www.ceres-solver.org/installation.html的方法.
我是ubuntu16.04的系统.但是再次catkin_make后出现以下问题.
不知道是什么原因?

[ 2%] Built target actionlib_msgs_generate_messages_eus
[ 2%] Built target lasercamcal_ros_generate_messages_py
[ 2%] Built target sensor_msgs_generate_messages_eus
[ 2%] Built target actionlib_msgs_generate_messages_cpp
[ 2%] Built target actionlib_generate_messages_nodejs
[ 2%] Built target lasercamcal_ros_generate_messages_cpp
[ 2%] Built target lasercamcal_ros_generate_messages_nodejs
[ 2%] Built target lasercamcal_ros_generate_messages_lisp
[ 5%] Built target lasercamcal_ros_generate_messages_eus
[ 5%] Built target lasercamcal_ros_generate_messages
In file included from /usr/local/include/ceres/internal/autodiff.h:152:0,
from /usr/local/include/ceres/autodiff_cost_function.h:130,
from /usr/local/include/ceres/ceres.h:37,
from /home/zjrobot/robot_perception/laser_cam_calibration/LaserCameraCal_ws/src/CamLaserCalibraTool/src/LaseCamCalCeres.cpp:11:
/usr/local/include/ceres/jet.h:981:8: error: ‘ScalarBinaryOpTraits’ is not a class template
struct ScalarBinaryOpTraits<ceres::Jet<T, N>, T, BinaryOp> {
^
/usr/local/include/ceres/jet.h:985:58: error: type/value mismatch at argument 3 in template parameter list for ‘template<class BinaryOp, class T, int N> struct Eigen::ScalarBinaryOpTraits’
struct ScalarBinaryOpTraits<T, ceres::Jet<T, N>, BinaryOp> {
^
/usr/local/include/ceres/jet.h:985:58: note: expected a constant of type ‘int’, got ‘BinaryOp’
CamLaserCalibraTool/CMakeFiles/lasercamcal.dir/build.make:662: recipe for target 'CamLaserCalibraTool/CMakeFiles/lasercamcal.dir/src/LaseCamCalCeres.cpp.o' failed
make[2]: *** [CamLaserCalibraTool/CMakeFiles/lasercamcal.dir/src/LaseCamCalCeres.cpp.o] Error 1
CMakeFiles/Makefile2:534: recipe for target 'CamLaserCalibraTool/CMakeFiles/lasercamcal.dir/all' failed
make[1]: *** [CamLaserCalibraTool/CMakeFiles/lasercamcal.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2

标定平移误差大,每次calibrate_offline会有不同

  1. 我在使用SR300和2D laser进行标定时,标定结果z轴高度方向误差大约30-40cm,且同一次的数据为什么每次执行calibr_offline的结果会不同

2.标定时使用kalibr_tag是否所有码块都需要在视野内,且旋转幅度是否不能过大

3.能否提供,代码现在默认的laser和camera的外参坐标系

带边界约束的结果比不带边界约束的结果更差

真值基本这样的
$ rosrun tf tf_echo /laser /middle_depth_optical_frame
At time 1658549856.810

  • Translation: [0.225, 0.033, 0.878]
  • Rotation: in Quaternion [-0.636, 0.636, -0.310, 0.310]
    in RPY (radian) [-2.234, 0.000, -1.571]
    in RPY (degree) [-127.999, 0.000, -90.000]
  1. 激光线多点不带边界约束的标定结果, 偏接近真实,但是激光与深度点云有距离偏差
    CamLaserCalibration(obs,Tcl, false);

Load apriltag pose size: 473
obs size: 28
------- Closed-form solution Tlc: -------
-0.202293 -0.871914 -0.445919 0.00021974
0.9705 -0.239472 0.0279725 0.000116325
-0.131175 -0.427106 0.894636 -1.74682e-08
0 0 0 1

Solver Summary (v 1.13.0-eigen-(3.3.4)-lapack-suitesparse-(5.1.2)-cxsparse-(3.1.9)-openmp)

                                 Original                  Reduced

Parameter blocks 1 1
Parameters 7 7
Effective parameters 6 6
Residual blocks 4633 4633
Residual 4633 4633

Minimizer TRUST_REGION

Dense linear algebra library EIGEN
Trust region strategy LEVENBERG_MARQUARDT

                                    Given                     Used

Linear solver DENSE_QR DENSE_QR
Threads 1 1
Linear solver threads 1 1
Linear solver ordering AUTOMATIC 1

Cost:
Initial 2.190158e-01
Final 1.212313e-02
Change 2.068927e-01

Minimizer iterations 38
Successful steps 27
Unsuccessful steps 11

Time (in seconds):
Preprocessor 0.0013

Residual evaluation 0.0260
Jacobian evaluation 0.0436
Linear solver 0.0086
Minimizer 0.0814

Postprocessor 0.0001
Total 0.0829

Termination: CONVERGENCE (Function tolerance reached. |cost_change|/cost: 4.138553e-07 <= 1.000000e-06)

----- H singular values--------:
51585.2
196.607
25.0317
4.7588
0.716847
0.0459204

recover chi2: 5295.55

----- Transform from Camera to Laser Tlc is: -----

0.00248544 -0.665906 0.746032 0.17585
-0.999886 0.00943778 0.0117553 -0.0469319
-0.0148688 -0.745976 -0.665807 0.871766
-0 -0 -0 1

----- Transform from Camera to Laser, euler angles and translations are: -----

roll(rad): -2.29947 pitch(rad): 0.0148694 yaw(rad): -1.56831
or roll(deg): -131.75 pitch(deg): 0.851951 yaw(deg): -89.8576
tx(m): 0.17585 ty(m): -0.0469319 tz(m): 0.871766

Result file : /home/kint/code/camera_laser_calib_ws/log/result.yaml

-------------- Calibration Code End --------------

  1. 激光线带边界约束的标定结果,基本就是错误的
    CamLaserCalibration(obs,Tcl, true, true);

Load apriltag pose from: /home/kint/code/camera_laser_calib_ws/log/apriltag_pose.txt
Load apriltag pose size: 473
obs size: 28
------- Closed-form solution Tlc: -------
-0.202293 -0.871914 -0.445919 0.00021974
0.9705 -0.239472 0.0279725 0.000116325
-0.131175 -0.427106 0.894636 -1.74682e-08
0 0 0 1

Solver Summary (v 1.13.0-eigen-(3.3.4)-lapack-suitesparse-(5.1.2)-cxsparse-(3.1.9)-openmp)

                                 Original                  Reduced

Parameter blocks 1 1
Parameters 7 7
Effective parameters 6 6
Residual blocks 112 112
Residual 112 112

Minimizer TRUST_REGION

Dense linear algebra library EIGEN
Trust region strategy LEVENBERG_MARQUARDT

                                    Given                     Used

Linear solver DENSE_QR DENSE_QR
Threads 1 1
Linear solver threads 1 1
Linear solver ordering AUTOMATIC 1

Cost:
Initial 4.483704e-01
Final 2.642021e-01
Change 1.841682e-01

Minimizer iterations 66
Successful steps 58
Unsuccessful steps 8

Time (in seconds):
Preprocessor 0.0000

Residual evaluation 0.0021
Jacobian evaluation 0.0045
Linear solver 0.0009
Minimizer 0.0085

Postprocessor 0.0000
Total 0.0086

Termination: CONVERGENCE (Function tolerance reached. |cost_change|/cost: 7.370300e-07 <= 1.000000e-06)

----- H singular values--------:
1.01335e+07
2.76495e+06
723721
19.434
3.18653
0.376837

recover chi2: 294957

----- Transform from Camera to Laser Tlc is: -----

-0.0570423 -0.692016 -0.719625 2.1592
0.994199 -0.105204 0.0223606 -0.344001
-0.091181 -0.714175 0.694003 -0.839734
-0 -0 -0 1

----- Transform from Camera to Laser, euler angles and translations are: -----

roll(rad): -0.799722 pitch(rad): 0.0913079 yaw(rad): 1.62811
or roll(deg): -45.8207 pitch(deg): 5.23156 yaw(deg): 93.2837
tx(m): 2.1592 ty(m): -0.344001 tz(m): -0.839734

Result file : /home/kint/code/camera_laser_calib_ws/log/result.yaml

-------------- Calibration Code End --------------

Cannot get the true z offset of camera w.r.t lidar

Hi @HeYijia , thanks for your open source.

Right now, I'm using your code to calibrate a 2d laser and mono camera, which are not at the same vertical level. I found that the tz value of camera w.r.t lidar is not correct while the tx, ty and orientation is almost same as the ground truth.

Since you only use point in plane constraints, and moving the lidar in the z direction doesn't change this constraints, so I'm guessing that the tz value is unobservable using your calibration method.

Correct me if I'm not right.

Thanks!

请问下如果采用棋盘格标定板

请问下如果采用棋盘格标定板,可以在原理上实现该方法的标定吗?
然后如果可行,修改成棋盘格标定的程序,麻烦吗?
谢谢啦!

原论文中一个地方求解析

大家好,原论文的流程了大概了解了。但是这个地方实在不懂是怎么得到的的。请大神帮个忙指点一下。谢谢啦

Screen Shot 2021-01-31 at 11 15 31 PM

还有在LaseCamCalCeres.cpp代码中第133行:Eigen::Vector4d planar_tag(0,0,1,0); // tag plane in tag frame
Eigen::Vector4d planar_cam = (Tctag.inverse()).transpose() * planar_tag; // plane parameters in camera frame

这个planar_tag为什么是0010?这个是homogenous coordinates?

多谢啦

April Tag Size

Couple of questions,

for the tag_descriptions parameters, how many tags should i provide parameters for, if i am only using 1 tag for the calibration?

Also, what is the "size" of an april tag? Is it the length of the outer square in meters?

代码解读

你好,代码LaseCamCalCeres.cpp中57行,在计算雅克比矩阵的时候 jaco_i.rightCols<3>() = planar_.head(3).transpose() * (-qcl.toRotationMatrix() * skewSymmetric(point_)); 这边我有点不理解?

我的理解雅克比矩阵应该这样计算:jaco_i.rightCols<3>() = planar_.head(3).transpose() *-skewSymmetric( qcl.toRotationMatrix() * point_+tcl);

能否直接优化H矩阵

贺博,请问一下,如果只想计算激光雷达和相机之间的转换矩阵,能否直接优化H矩阵,我尝试了一下,结果不对

Frames of reference

For the output of the "roslaunch lClibra example.launch", the camera to laser transform is provided, what frame orientations does this assume? For the laser, is it x forward, y left, z upwards? for camera, is it z inwards (into the image), x (right), y (down). everything mentioned is for the positive axis

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.