Coder Social home page Coder Social logo

jhu-lcsr / handeye_calib_camodocal Goto Github PK

View Code? Open in Web Editor NEW
531.0 24.0 178.0 109 KB

Easy to use and accurate hand eye calibration which has been working reliably for years (2016-present) with kinect, kinectv2, rgbd cameras, optical trackers, and several robots including the ur5 and kuka iiwa.

License: BSD 2-Clause "Simplified" License

CMake 36.19% Python 1.76% C++ 62.05%
hand-eye-calibration ros robot-arm rotation orientations kinematics solver translation camera-calibration camera

handeye_calib_camodocal's Introduction

ROS + CamOdoCal Hand Eye Calibration

This is a ROS node integrating the Hand Eye Calibration implemented in CamOdoCal. See this stack exchange question explaining how Hand Eye Calibration works.

Example uses include determining exact transforms with both positions and orientations of a:

  • camera attached to the floor is relative to a robot arm
  • camera attached to a robot arm tip relative to a robot arm
  • set of cameras attached to a moving vehicle (this is what camodocal itself implements)
  • two robot arms bolted together

keynote presentation explaining many details about hand eye calibration for those that are interested. Practical code and instructions to calibrate your robot can be found below.

Hand Eye Calibration Basics

Two Common Solutions to Hand Eye Calibration

AX=XB Hand Eye Calibration Solution

AX=ZB Hand Eye Calibration Solution

Feeding data into CamOdoCal

  1. Each measurement taken at a different time, position, and orientation narrows down the possible transforms that can represent the unknown X

  2. Record a list of many transforms A and B taken between different time steps, or relative to the first time step

    • Rotations are in AxisAngle = UnitAxis*Angle format, or [x_axis,y_axis,z_axis]*𝜃_angle
      • ||UnitAxis||=1
      • || AxisAngle || = 𝜃_angle
    • Translations are in the normal [x,y,z] format
  3. Pass both vectors into EstimateHandEyeScrew()

  4. Returns X in the form of a 4x4 transform estimate

Camodocal Hand Eye Calibration Details

When using this with a robot arm, move it around to a variety of poses and orientations, make sure any data sources that lag behind settle down, then record each pair of poses between the robot base and the robot tip, and between the eye/camera base and the marker, fiducial, or AR tag it is viewing.

This will save out a yaml file with the results. Be sure to load the results into your system using the data formatted as a rotation matrix, dual quaternion, or quaternion + translation. Roll Pitch Yaw can degenerate and will often be inaccurate!

Installation

Linux

All dependencies can be installed via scripts in the robotics_setup repository on Ubuntu 14.04 or Ubuntu 16.04.

MacOS

On OS X you can use homebrew and the homebrew-robotics tap to install all dependencies.

ROS (both Linux + MacOS)

Once you've completed the Linux or MacOS steps, follow normal ros source package installation procedures with catkin build.

Dependencies

If installing manually, be sure to follow the instructions for each library as there are specific steps required depending on your OS.

  • ROS indigo or kinetic
  • OpenCV 2 or 3 with (recommended) nonfree components
    • Note handeye_calib_camodocal does not call any nonfree components, but some users have had difficulty configuring CMake to compile and install all the other dependencies without them.
    • OpenCV3 puts their nonfree components in opencv-contrib.
  • Eigen3
  • ceres-solver
  • glog
    • If you encounter an error about providing "FindGlog.cmake" in CMAKE_MODULE_PATH, try installing glog from source.
  • gflags

Examples

There are example pre-recorded transforms in the example folder, all config files are expected to be in handeye_calib_camodocal/launch folder by default, but if that doesn't work try checking the ~/.ros/ folder.

To verify that the software is working run:

roslaunch handeye_calib_camodocal handeye_example.launch

You should see output like the following:

# INFO: Before refinement: H_12 =
  -0.962926   -0.156063     0.22004 -0.00802514
  -0.176531    0.981315  -0.0765322   0.0242905
  -0.203985   -0.112539   -0.972484   0.0550756
          0           0           0           1
Ceres Solver Report: Iterations: 89, Initial cost: 1.367791e+01, Final cost: 6.005694e-04, Termination: CONVERGENCE
# INFO: After refinement: H_12 =
  -0.980558    0.184959   0.0655414  0.00771561
  0.0495028  -0.0900424    0.994707   0.0836796
   0.189881    0.978613   0.0791359 -0.00867321
          0           0           0           1
Result from /ee_link to /ar_marker_0:
  -0.980558    0.184959   0.0655414  0.00771561
  0.0495028  -0.0900424    0.994707   0.0836796
   0.189881    0.978613   0.0791359 -0.00867321
          0           0           0           1
Translation (x,y,z) :  0.00771561   0.0836796 -0.00867321
Rotation (w,x,y,z): -0.046193, 0.0871038, 0.672938, 0.733099

Result from /ar_marker_0 to /ee_link:
  -0.980558    0.184959   0.0655414  0.00771561
  0.0495028  -0.0900424    0.994707   0.0836796
   0.189881    0.978613   0.0791359 -0.00867321
          0           0           0           1
Inverted translation (x,y,z) : 0.00507012 0.0145954 -0.083056
Inverted rotation (w,x,y,z): -0.046193, 0.0871038, 0.672938, 0.733099
0.046193 0.0871038 0.672938 0.733099

Writing calibration to "/home/cpaxton/catkin_ws/src/handeye_calib_camodocal/launch/CalibratedTransform.yml"...
[handeye_calib_camodocal-1] process has finished cleanly
log file: /home/cpaxton/.ros/log/a829db0a-f96b-11e6-b1dd-fc4dd43dd90b/handeye_calib_camodocal-1*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete
done

The full terminal session can be found at:

Recording your own Transforms

To record your own session, modify launch/handeye_file.launch to specify the ROS topics that will publish the poses between which you wish to calibrate, then run:

roslaunch handeye_calib_camodocal handeye_file.launch

If you have difficulty we cover just about every problem we've seen below in the troubleshooting section. It can also help to see this stack exchange question explaining how Hand Eye Calibration works

After you run, be sure to back up TransformPairsInput.yml and CalibratedTransform.yml so you don't lose all the transforms and positions you saved!

How do I get transforms between the camera and an object it sees?

If a camera is calibrated it is possible to estimate the transform from the camera to a printed pattern with known dimensions. I don’t recommend using a checkerboard for hand eye calibration because the pattern is ambiguous. Use something like:

They provide instructions on how to set up your camera and create patterns that can be used to generate transforms.

Troubleshooting

Saved Files Not Loading?

If you have trouble finding the saved files, the default working directory of ROS applications is in the ~/.ros/ folder, so try looking there. Be sure to also check your launch file which is typically launch/handeye_file.launch this determines if transforms will be loaded from a running robot or saved files, as well as where save files are placed.

Collecting Enough Data

We recommend you collect at least ~36 accurate transforms for a good calibration. If it fails to converge (i.e. you don't get a good result out), then you probably have your transforms flipped the wrong way or there is too much noise in your data to find a sufficiently accurate calibration.

Eliminating Sensor Noise

One simple method to help deal with this problem is to create a new node that reads the data you want to read and save a rolling average of the pose. This helps to stabilize the results. There are better methods such as a kalman filter that could handle this even better. If you take a rolling average, make sure each time you take the data the robot has been set in a single position for the entire duration of the time for which the rolling average is being taken, because any error here will throw off the results.

Examples of "too much noise" when taking data

If there is too much noise you will probably see the following error:

normalization could not be handled. Your rotations and translations are probably either not aligned or not passed in properly

That means there is probably too much variation in the data you are reading to get an accurate solution. For example, if you watch the pose of an AR tag and it wobbles a little or flips this will prevent an accurate solution from being found. One way to help this is to ensure the system is completely stationary and then interpolate (average) the poses across several frames, again ensuring the system is completely stationary before recording the frame and then finally moving to the next position and repeating the process.

Your cameras must be calibrated

Camera calibration is very important! If they aren't calibrated then the poses being fed into the algorithm will be inaccurate, won't correspond, and thus the algorithm won't be able to find even a decent approximate solution and will just exit, printing an error.

Your robot and cameras must be rigidly fixed

Hand eye calibration solves for a rigid body transform, so if the whole system isn't rigidly fixed the transform you are solving for is constantly changing and thus impossible to find accurately. For example, if you have a camera and a fixed robot base, check that your robot is securely bolted to a surface. Tighten those bolts up! Also ensure the camera is securely and rigidly fixed in place in a similar fasion. Check for any wobbling and make sure to wait for everything to become still before taking your data points.

Sanity Check by Physically Measuring

Slight distortion or variation in time stamp while the arm moves slightly as you hold it can still throw it off. One additional way to test that is to have the arm go to two distant positions, and the length of the change in checkerboard poses should be equal to the length of the change in end effector tip poses assuming you can keep the orientation constant.

Sanity Check via Simulation

If you’re concerned it is a bug in the algorithm you can run it in simulation with v-rep or gazebo (os + v-rep python script is in the repo) to verify it works, since that will avoid all physical measurement problems. From there you could consider taking more real data and incorporating the real data to narrow down the source of the problem.

Sanity Check Transforms and when loading from files

If you're loading from a file you've modified by hand, check if your matrices are transposed, inverted, or in very unusual cases even just the 3x3 Rotation component of the 4x4 rotation matrix may be transposed.

Example output

Here is an example output of what you should expect when a run is executed successfully:

Writing pairs to "/home/cpaxton/catkin_ws/src/handeye_calib_camodocal/launch/TransformPairsInput.yml"...
q[ INFO] [1473813682.393291696]: Calculating Calibration...
# INFO: Before refinement: H_12 =
-0.00160534     0.99916   0.0409473 -0.00813108
-0.00487176  -0.0409546    0.999149     0.10692
  0.999987  0.00140449  0.00493341   0.0155885
         0           0           0           1
Ceres Solver Report: Iterations: 99, Initial cost: 1.882582e-05, Final cost: 1.607494e-05, Termination: CONVERGENCE
# INFO: After refinement: H_12 =
-0.00282176     0.999009    0.0444162  -0.00746998
  0.0121142   -0.0443789     0.998941     0.101617
   0.999923   0.00335684    -0.011977 -0.000671928
          0            0            0            1
Result:
-0.00282176     0.999009    0.0444162  -0.00746998
  0.0121142   -0.0443789     0.998941     0.101617
   0.999923   0.00335684    -0.011977 -0.000671928
          0            0            0            1
Translation:  -0.00746998     0.101617 -0.000671928
Rotation: -0.48498 0.513209 0.492549 0.513209

Note that this run is not a perfect one with errors of 5 mm over a motion of 1 m.

Cost

One key piece of information is the output of the cost function, which is a metric representing an estimate of solution accuracy:

Initial cost: 1.882582e-05, Final cost: 1.607494e-05

With a really good run where the calibration is dead on the final cost should be on the order of 1e-13 or 1e-14.

Results

Now lets take a look at the results:

Translation:  -0.00746998     0.101617 -0.000671928
Rotation: -0.48498 0.513209 0.492549 0.513209

The translation is in xyz format, and the rotation is in quaternion format. It is important to note that this tool and camodocal use the eigen Quaternion format which orders the four values stored in a quaternion wxyz. ROS launch files, by comparison store the data in the order xyzw. That means when copying the results into ROS you must move the first entry of the rotation to the end.

Here is an example of all 7 numbers from above correctly put into a ros launch file:

<node pkg="tf" type="static_transform_publisher" name="endpoint_to_marker" args=" -0.00746998     0.101617 -0.000671928  0.513209 0.492549 0.513209  -0.48498   $(arg ee_frame) /endpoint_marker 10"/>

Questions? Here is what we need to know.

If you try running this and have a question please create a diagram of your use case so we can understand how you are setting up the equations, then create a github issue.

See this stack exchange question explaining of how Hand Eye Calibration works for an example of such a diagram.

Authors

Andrew Hundt [email protected] Felix Jonathan [email protected]

Acknowledgements

Hand-Eye Calibration Using Dual Quaternions

@article{daniilidis1999hand,
  title={Hand-eye calibration using dual quaternions},
  author={Daniilidis, Konstantinos},
  journal={The International Journal of Robotics Research},
  volume={18},
  number={3},
  pages={286--298},
  year={1999},
  publisher={SAGE Publications}
}

CamOdoCal

Lionel Heng, Bo Li, and Marc Pollefeys,
CamOdoCal: Automatic Intrinsic and Extrinsic Calibration of a Rig with Multiple Generic Cameras and Odometry,
In Proc. IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), 2013.

Lionel Heng, Mathias Bürki, Gim Hee Lee, Paul Furgale, Roland Siegwart, and Marc Pollefeys,
Infrastructure-Based Calibration of a Multi-Camera Rig,
In Proc. IEEE International Conference on Robotics and Automation (ICRA), 2014.

Lionel Heng, Paul Furgale, and Marc Pollefeys,
Leveraging Image-based Localization for Infrastructure-based Calibration of a Multi-camera Rig,
Journal of Field Robotics (JFR), 2015.

References

  • Strobl, K., & Hirzinger, G. (2006) . Optimal hand-eye calibration. In 2006 IEEE/RSJ international conference on intelligent robots and systems (pp. 4647–4653), October 2006.
  • Technical University of Munich (TUM) CAMP lab wiki

  • K. Daniilidis, “Hand–Eye Calibration Using Dual Quaternions,” Int. Journal of Robs. Research, vol. 18, no. 3, pp. 286–298, June 1999.
  • E. Bayro–Corrochano, K. Daniilidis, and G. Sommer, “Motor–Algebra for 3D Kinematics: The Case of Hand–Eye Calibration,” Journal for Mathem. Imaging and Vision, vol. 13, no. 2, pp. 79–100, Oct. 2000.
  • F. Dornaika and R. Horaud, “Simultaneous Robot–World and Hand– Eye Calibration,” IEEE Trans. on Robs. and Aut., vol. 14, no. 4, pp. 617–622, August 1998.
  • Note: figures and text are from mixed sources including the presentation author, the various papers referenced, and the TUM wiki.

handeye_calib_camodocal's People

Contributors

ahundt avatar cpaxton avatar fjonath1 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

handeye_calib_camodocal's Issues

Calibrated values has high deviation

I have been attempting to perform calibration using the calibration methods mentioned above. While I achieved consistent results with the provided sample dataset, I encountered significant variations when using custom datasets. The dataset pertains to a UR robot, where T1_0 represents the transformation from the end effector (ee) to the base, and T1_1 contains information about the transformation from the camera to the object.

The calibration object consists of two spheres separated by a distance on a flat plate. I employ a line profile sensor to gather information about the sphere centers (tx, ty, tz) and components along the I, J, K directions in the x, y, and z axes. This information is used to construct a transformation matrix. After several iterations, I observed convergence, but there is a persistent small deviation of 6mm along the x, y, and z axes, particularly with a relatively large error along the z-axis. The units are in mm and radians.
output.json

Before refinement:

[[-2.52663337e-01 -9.56706422e-01 1.44478578e-01 -7.88199806e+01] [-9.65231410e-01 2.38889981e-01 -1.06112684e-01 -1.68174602e+02] [ 6.70042015e-02 -1.66266047e-01 -9.83801829e-01 5.02880690e+02] [ 0.00000000e+00 0.00000000e+00 0.00000000e+00 1.00000000e+00]]

After refinement: Ceres Solver Report: Iterations: 24, Initial cost: 9.949470e+05, Final cost: 2.781073e+02, Termination: CONVERGENCE

[[-8.02416568e-02 -9.95705290e-01 4.61763116e-02 -7.51493052e+01] [-9.96358056e-01 8.14624242e-02 2.51892252e-02 -6.68584297e+01] [-2.88426791e-02 -4.39869149e-02 -9.98615667e-01 3.76285022e+02] [ 0.00000000e+00 0.00000000e+00 0.00000000e+00 1.00000000e+00]]

Variance of about 1.5cm on the final transform.

The transforms I have are:

Robot Base -> Forearm link
Kinect link (A kinect mounted on the forearm) -> ARUCO marker

The transform I need is:
Forearm link -> Optical Tracker Base

screenshot from 2018-04-13 11-16-25

I manage to collect about 500 input pairs. For each one of them, I ensure that the position of the marker is stable. The position is not wobbly. I use the AR_track_alvar package to do the tracking.

To evaluate the precision of the calibration, I then randomly sample 50 pairs, run the solver and iterate a few 100 times. No matter which ARUCO marker/size/tracking precision threshold I use, I always end up with about 1.5 cm variance on the optical tracker position with respect to the forearm link. The final cost never goes below 1e-9 so I guess the solver is not able to converge properly.

What kind of precision is expected when the solver converge down to 1e-14 ? Has anyone experience similar problem in a similar setup? when using a kinect ? The AR track alvar library ?

AX = ZB solution

Does this package implement the AX = ZB solution?
As far as I've noticed, the AX=XB is implemented only, unless I missed something.

Monocular camera

Hi,
is it possible to use this code on Ubuntu 16.04 for calibrating a monocular camera mounted on the wrist of a kinova jaco2 manipulator?

Thank you very much

Eye-on-Base Calibration

Hello,

First of all, I will try to explain my problem. If you need more information, just let me know. And of course, thank you for providing this code.

My setup:

  • I have a robot with a marker fixed to its end effector.
  • I have a camera in a fixed position.

What I want:

  • I want to estimate the transform between camera frame and robot base frame (eye-on-base).

Why I want:

I was previously using easy_handeye. The output of their method was accurate but had some rotation errors which led to over 10mm error in conversion from camera frame to robot motion.

I am trying to use your method because it seems more accurate. Since ceres library seems promising into refining a estimate, and the dual quaternion solution seems more robust to rotation errors than the classic ones implemented in VISP.

How I am testing it:

Currently I have a simulation. So I know exactly the transform between camera-robotBase and marker-endEffector, so I can compare the output of your method with my "ground-truth" simulation.

I am not using your workflow exactly, I basically integrated your method estimateHandEyeScrew() in my system (I am doing the correct conversions from TF2 data to Eigen and vice versa). How do I know it is right? because I can estimate the transform from endeffector-marker and it is correct, the same transform you provide an example.

What is my problem?

I cannot estimate the transform camera-robotBase. I am providing the method with pairs of transforms endEffector-robotBase and camera-Marker. The resulting output is messy and very far from the reality. The method does not output convergence error. I am providing over 40 transform pairs. I provided 15, 25, 40 and even 60 samples.

However, when I provide the pairs of transforms robotBase-endEffector and camera-Marker I can obtain the transform marker-endEffector accurately.

I am doing something wrong? I have been struggling with this issue for a couple hours now.

example runs failed

OS: ubuntu16.04
The following example doesn't work...

# roslaunch handeye_calib_camodocal handeye_file.launch

terminal output:

... logging to /home/yongqi/.ros/log/19d39188-2cb1-11e7-a55b-0c82683d98b6/roslaunch-yongqi-OptiPlex-7010-27081.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://yongqi-OptiPlex-7010:41028/

SUMMARY
========

PARAMETERS
 * /handeye_calib_camodocal/ARTagTF: /ar_marker_0
 * /handeye_calib_camodocal/EETF: /ee_link
 * /handeye_calib_camodocal/baseTF: /base_link
 * /handeye_calib_camodocal/cameraTF: /camera_link
 * /handeye_calib_camodocal/load_transforms_from_file: True
 * /handeye_calib_camodocal/output_calibrated_transform_filename: /home/yongqi/catk...
 * /handeye_calib_camodocal/transform_pairs_record_filename: /home/yongqi/catk...
 * /rosdistro: kinetic
 * /rosversion: 1.12.7

NODES
  /
    handeye_calib_camodocal (handeye_calib_camodocal/handeye_calib_camodocal)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[handeye_calib_camodocal-1]: started with pid [27099]
Calibrated output file: /home/yongqi/catkin_ws/src/handeye_calib_camodocal/launch/CalibratedTransform.yml
Transform pairs loading file: TransformPairsOutput.yml
[ INFO] [1493537679.566074523]: Adding first transformation.
EE transform: 
  0.638483   0.767534  0.0568427   0.612118
0.00850229  0.0668179  -0.997729 -0.0399105
 -0.769589   0.637516  0.0361363   0.261381
         0          0          0          1
Cam transform: 
-0.164386 -0.213826 -0.962941  0.764291
 0.161875  0.957139 -0.240171 -0.122489
 0.973023 -0.195357 -0.122727  0.200385
        0         0         0         1
[ INFO] [1493537679.592253502]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.215213 vs Cam:0.246387
EE transform: 
 0.433981  0.775651 -0.458286   0.61283
-0.578521 -0.150023 -0.801752 -0.251463
-0.690633  0.613073  0.383623  0.221866
        0         0         0         1
Cam transform: 
 -0.127277  -0.111455  -0.985585   0.752881
 -0.464759   0.884533 -0.0400092   0.117874
  0.876242   0.452967   -0.16438   0.147451
         0          0          0          1
[ INFO] [1493537679.592787035]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.195441 vs Cam:0.216132
EE transform: 
 0.709849  0.661286  0.242519  0.603354
 0.483669 -0.207335 -0.850339 -0.226261
-0.512035  0.720911  -0.46702  0.203122
        0         0         0         1
Cam transform: 
 -0.0013274  0.00287129   -0.999995    0.775879
   0.647853    0.761765   0.0013273   0.0894315
   0.761765   -0.647848 -0.00287134    0.159541
          0           0           0           1
[ INFO] [1493537679.593285912]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.229358 vs Cam:0.245743
EE transform: 
  0.456608   0.884121 -0.0991898   0.443182
  0.285236  -0.251085  -0.924985  -0.192034
 -0.842704   0.394063  -0.366831   0.230983
         0          0          0          1
Cam transform: 
-0.378376  0.174054 -0.909141  0.879284
 0.348826  0.936566 0.0341261 0.0882483
  0.85741  -0.30422 -0.415088  0.252881
        0         0         0         1
[ INFO] [1493537679.593808575]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.387457 vs Cam:0.366207
EE transform: 
  0.323211   0.940599   0.103963   0.248849
-0.0689631   0.132979  -0.988717  -0.173242
 -0.943811   0.312394   0.107847    0.24186
         0          0          0          1
Cam transform: 
 -0.505514   -0.28428  -0.814641     1.0135
-0.0235831   0.948363   -0.31631  0.0714151
  0.862496  -0.140688  -0.486115   0.385871
         0          0          0          1
[ INFO] [1493537679.594311224]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.342398 vs Cam:0.342725
EE transform: 
   0.46462    0.88284  0.0687151   0.432093
 0.0525137  0.0499925  -0.997368   -0.31921
 -0.883951   0.467006 -0.0231337   0.178805
         0          0          0          1
Cam transform: 
-0.395441 -0.197478 -0.897011  0.902994
   0.1456  0.950787 -0.273503  0.190431
 0.906878 -0.238759 -0.347227  0.217779
        0         0         0         1
[ INFO] [1493537679.594814846]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.290927 vs Cam:0.272425
EE transform: 
-0.153963  0.959983  0.233939  0.371358
0.0283561  0.240958 -0.970121 -0.201852
 -0.98767 -0.142729  -0.06432  0.282538
        0         0         0         1
Cam transform: 
-0.824707 -0.238584 -0.512772  0.934864
-0.013887  0.914932 -0.403368  0.065755
 0.565389  -0.32554 -0.757865  0.298794
        0         0         0         1
[ INFO] [1493537679.595326427]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.190786 vs Cam:0.145262
EE transform: 
 0.418462   0.80981  0.411214  0.593949
-0.250154  0.538016  -0.80496 -0.228291
-0.873105  0.233978  0.427717  0.285505
        0         0         0         1
Cam transform: 
-0.367026 -0.701436 -0.610965  0.762706
-0.197372  0.700571 -0.685743 0.0218338
  0.90903 -0.131098 -0.395572   0.18397
        0         0         0         1
[ INFO] [1493537679.595857897]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.217562 vs Cam:0.181829
EE transform: 
 0.677224  0.731047 0.0832987  0.642735
-0.494061  0.535712 -0.684774 -0.252373
-0.545226  0.422591  0.723979  0.225948
        0         0         0         1
Cam transform: 
   0.0976 -0.689456 -0.717722  0.753887
-0.346197  0.652607 -0.673983 0.0429672
 0.933071  0.314254 -0.174993  0.125701
        0         0         0         1
[ INFO] [1493537679.596374713]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.0645175 vs Cam:0.0572455
EE transform: 
  0.612387   0.763326   0.205709   0.637671
  0.164239   0.131689  -0.977591 -0.0885319
  -0.77331   0.632449 -0.0447231   0.227536
         0          0          0          1
Cam transform: 
 -0.174813  -0.263647  -0.948647   0.765482
  0.297239   0.904399  -0.306124 -0.0875266
  0.938663   -0.33549 -0.0797345   0.155072
         0          0          0          1
[ INFO] [1493537679.596866538]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.166543 vs Cam:0.155018
EE transform: 
  0.624052   0.778644 -0.0653676   0.682684
  -0.40703   0.252525  -0.877814  -0.190556
 -0.666998   0.574408    0.47452   0.253441
         0          0          0          1
Cam transform: 
  -0.0156266    -0.445582    -0.895105     0.701242
   -0.243935     0.869863    -0.428758 -0.000550737
    0.969666     0.211647    -0.122286     0.128369
           0            0            0            1
[ INFO] [1493537679.597348153]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.107402 vs Cam:0.10879
EE transform: 
  0.643567   0.765191  0.0174386   0.712786
  0.254161  -0.192161   -0.94788 -0.0317913
 -0.721958   0.614456   -0.31815   0.224841
         0          0          0          1
Cam transform: 
 -0.0989447   0.0423206   -0.994193    0.718351
   0.387674    0.921796 0.000656462   -0.125335
   0.916471   -0.385358   -0.107613    0.101812
          0           0           0           1
[ INFO] [1493537679.597837399]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.186286 vs Cam:0.167712
EE transform: 
 0.631684  0.773867 0.0458826  0.718126
 0.351244 -0.232942 -0.906844  0.112637
-0.691089  0.588954 -0.418962  0.247451
        0         0         0         1
Cam transform: 
 -0.11272  0.100454 -0.988536  0.722855
 0.495192  0.868203 0.0317608 -0.267481
  0.86144 -0.485935 -0.147608  0.126984
        0         0         0         1
[ INFO] [1493537679.598309160]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.122085 vs Cam:0.11748
EE transform: 
 0.214104  0.968786  0.124954  0.528412
 0.820688 -0.109032 -0.560877 0.0474746
-0.529745  0.222634 -0.818415  0.245198
        0         0         0         1
Cam transform: 
-0.354624  0.433515 -0.828436  0.862123
  0.85652  0.505959  -0.10188 -0.185446
 0.374988 -0.745701 -0.550739  0.216721
        0         0         0         1
[ INFO] [1493537679.598798316]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.115361 vs Cam:0.135141
EE transform: 
 0.593263  0.798971   0.09841  0.633696
 0.363423 -0.156741 -0.918344 -0.143423
-0.718306  0.580584 -0.383353  0.215253
        0         0         0         1
Cam transform: 
  -0.177395   0.0416623   -0.983258    0.763908
   0.501263    0.863618  -0.0538427 -0.00403508
   0.846916   -0.502422   -0.174085    0.135334
          0           0           0           1
[ INFO] [1493537679.599272100]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.202728 vs Cam:0.135966
EE transform: 
  0.771397   0.281163  -0.570871   0.776923
 -0.522504  -0.232209  -0.820407  0.0369184
  -0.36323   0.931142 -0.0322165   0.171742
         0          0          0          1
Cam transform: 
 0.373449  0.257277  -0.89126  0.726359
 -0.31825  0.937994  0.137417 -0.182011
 0.871351  0.232326  0.432172 0.0841736
        0         0         0         1
[ INFO] [1493537679.599755426]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.211066 vs Cam:0.192321
EE transform: 
  0.59232  0.312115 -0.742793  0.756832
-0.766905 -0.064235 -0.638538 -0.180032
-0.247011   0.94787  0.201315  0.198352
        0         0         0         1
Cam transform: 
   0.35259   0.253018  -0.900923   0.686074
 -0.621796   0.782826 -0.0234983  0.0204989
  0.699321   0.568476   0.433343  0.0982884
         0          0          0          1
[ INFO] [1493537679.600241630]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.218805 vs Cam:0.188602
EE transform: 
  0.786341   0.439637   0.434036   0.770384
  0.479322 0.00908998  -0.877592  0.0902576
 -0.389767    0.89813   -0.20358   0.184675
         0          0          0          1
Cam transform: 
 0.134203 -0.329043  -0.93473  0.728758
 0.671974   0.72348 -0.158201 -0.274474
 0.728313 -0.606883  0.318201 0.0945141
        0         0         0         1
[ INFO] [1493537679.600736906]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.102906 vs Cam:0.101342
EE transform: 
 0.665485  0.675559  0.317412  0.554426
 0.414056 0.0197006 -0.910038 0.0117472
-0.621038  0.737043 -0.266609  0.193611
        0         0         0         1
Cam transform: 
-0.0879954  -0.170409  -0.981436   0.857683
  0.528511   0.827159  -0.191008  -0.159951
  0.844354  -0.535508  0.0172769   0.212416
         0          0          0          1
[ INFO] [1493537679.601212578]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.245913 vs Cam:0.226488
EE transform: 
  0.211806     0.9765 -0.0398361   0.468647
 -0.961238   0.200787  -0.188962  -0.233015
 -0.176523  0.0783153   0.981176   0.312372
         0          0          0          1
Cam transform: 
 0.122497 -0.698436 -0.705111  0.814256
-0.912926   0.19939 -0.356104 0.0879747
 0.389308  0.687336 -0.613196  0.267508
        0         0         0         1
[ INFO] [1493537679.601692677]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.203669 vs Cam:0.170966
EE transform: 
  0.621962   0.782692 -0.0235887   0.679652
 -0.719302   0.559166  -0.412236  -0.231721
 -0.309464   0.273363   0.910771   0.250024
         0          0          0          1
Cam transform: 
 0.283423 -0.704145 -0.651038   0.71956
-0.592429  0.405286 -0.696255 0.0135736
 0.754122  0.583029 -0.302288  0.107028
        0         0         0         1
[ INFO] [1493537679.602164631]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.328268 vs Cam:0.288981
EE transform: 
  0.67922  0.733721 0.0177239  0.632855
-0.608679  0.576631 -0.544983 -0.365025
-0.410086  0.359375  0.838259  0.221003
        0         0         0         1
Cam transform: 
 0.295033 -0.721063 -0.626916   0.74937
-0.502125  0.441212 -0.743776  0.152977
 0.812912  0.534228 -0.231892  0.114329
        0         0         0         1
[ INFO] [1493537679.602650480]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.249251 vs Cam:0.18365
EE transform: 
  0.812029   0.579104 -0.0724385    0.69914
  0.414438   -0.65957  -0.627064   0.192743
 -0.410913   0.479173  -0.775592   0.240755
         0          0          0          1
Cam transform: 
 0.216836  0.465516 -0.858066  0.764563
 0.607482   0.62371  0.491886  -0.29749
 0.764165 -0.627918  -0.14755  0.144691
        0         0         0         1
[ INFO] [1493537679.603121882]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.170334 vs Cam:0.152798
EE transform: 
  0.804583   0.591943 -0.0474213   0.501879
  0.229391  -0.383462  -0.894615  0.0897372
 -0.547746   0.708915  -0.444314   0.268606
         0          0          0          1
Cam transform: 
 0.131482  0.169286 -0.976757  0.852262
 0.443435  0.871194  0.210682 -0.185114
  0.88661 -0.460829  0.039479  0.308489
        0         0         0         1
[ INFO] [1493537679.603598426]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.112103 vs Cam:0.105423
EE transform: 
 0.0667841   0.853922  -0.516098   0.709308
 -0.751424   0.383345   0.537037 -0.0759432
  0.656431   0.351943   0.667259   0.304078
         0          0          0          1
Cam transform: 
   0.59165 -0.0364445  -0.805371   0.670302
 -0.730477  -0.446907  -0.516408  -0.127621
 -0.341105   0.893838  -0.291034   0.152911
         0          0          0          1
[ INFO] [1493537679.604095246]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.249415 vs Cam:0.238847
EE transform: 
 -0.317105   0.928469  -0.193362   0.620601
-0.0520595   0.186536   0.981068  -0.272426
   0.94696   0.321168 -0.0108159   0.351227
         0          0          0          1
Cam transform: 
 0.442358  0.298281 -0.845782  0.660235
-0.106876 -0.918817 -0.379937 0.0909693
-0.890448  0.258462 -0.374567  0.225992
        0         0         0         1
[ INFO] [1493537679.604582524]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.162403 vs Cam:0.144185
EE transform: 
 -0.31537  0.918887  0.237041  0.661038
  0.24915  -0.16085  0.955014  0.100551
 0.915678  0.360242 -0.178213   0.32659
        0         0         0         1
Cam transform: 
  0.370902  0.0925142  -0.924053   0.706948
   0.15567   -0.98714 -0.0363468  -0.253602
 -0.915532  -0.130366  -0.380534   0.218013
         0          0          0          1
[ INFO] [1493537679.605068559]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.167866 vs Cam:0.147663
EE transform: 
0.0108778  0.742046  -0.67026  0.684698
-0.848225  0.361808  0.386793 -0.190969
 0.529524  0.564324  0.633358   0.25176
        0         0         0         1
Cam transform: 
    0.52301   0.0384859   -0.851457    0.699199
  -0.828886   -0.209705   -0.518624 -0.00268676
  -0.198515    0.977007  -0.0777775    0.143686
          0           0           0           1
[ INFO] [1493537679.605563702]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.174251 vs Cam:0.169405
EE transform: 
  0.127525   0.713096  -0.689371   0.664034
  -0.98397   0.178315 0.00242873  -0.189673
  0.124657   0.678011   0.724405   0.188995
         0          0          0          1
Cam transform: 
  0.297171 -0.0324921  -0.954271   0.751153
 -0.946831   0.119021  -0.298906  0.0243991
  0.123291    0.99236   0.004605   0.117024
         0          0          0          1
[ INFO] [1493537679.606031131]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.174251 vs Cam:0.169444
EE transform: 
  0.127537   0.713093  -0.689371   0.664035
 -0.983968   0.178331 0.00242899  -0.189672
  0.124668   0.678009   0.724405   0.188996
         0          0          0          1
Cam transform: 
  0.297921 -0.0320348  -0.954053   0.751255
 -0.946797   0.117537  -0.299602  0.0244031
  0.121734   0.992552 0.00468615   0.116934
         0          0          0          1
[ INFO] [1493537679.606507513]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.194746 vs Cam:0.169552
EE transform: 
 0.301047  0.820638   0.48572  0.688924
 0.849563 -0.462156  0.254272  0.118761
 0.433143  0.336102 -0.836315  0.178614
        0         0         0         1
Cam transform: 
 0.338239  0.251229 -0.906906  0.795671
 0.910939 -0.329279  0.248527 -0.244215
-0.236188 -0.910198 -0.340229 0.0866057
        0         0         0         1
[ INFO] [1493537679.606976695]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.201437 vs Cam:0.157416
EE transform: 
  0.36784  0.914939  0.166073  0.470847
 0.898307 -0.395784  0.190785 0.0952608
 0.240286 0.0790065 -0.967482  0.309837
        0         0         0         1
Cam transform: 
  0.276986   0.543839  -0.792161   0.863331
  0.958611  -0.212945   0.188995  -0.191875
-0.0659045  -0.811723  -0.580313   0.301165
         0          0          0          1
[ INFO] [1493537679.607457110]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.239668 vs Cam:0.218786
EE transform: 
 0.713634  0.676834  0.180616  0.425799
 0.584897  -0.43381  -0.68535 0.0983482
-0.385516  0.594731  -0.70546  0.201296
        0         0         0         1
Cam transform: 
 0.125093  0.264966 -0.956109  0.952171
 0.729179  0.628936  0.269699    -0.172
 0.672793 -0.730912 -0.114532   0.30097
        0         0         0         1
[ INFO] [1493537679.607958114]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.348903 vs Cam:0.289647
EE transform: 
 0.662312  0.605825  0.440815  0.571357
  0.74147 -0.614447 -0.269586  0.290935
 0.107535  0.505401 -0.856157  0.158362
        0         0         0         1
Cam transform: 
 0.432265  0.214714 -0.875811  0.915636
 0.862817  0.183809  0.470914  -0.36924
 0.262094 -0.959225 -0.105805  0.190188
        0         0         0         1
[ INFO] [1493537679.608427480]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.185299 vs Cam:0.127593
EE transform: 
  0.497426   0.845774   -0.19296   0.578632
  0.858999  -0.511284 -0.0266528   0.135965
   -0.1212  -0.152494  -0.980845   0.309152
         0          0          0          1
Cam transform: 
 0.171758  0.808071  -0.56349  0.820531
 0.943272 0.0300799  0.330656  -0.23634
 0.284143 -0.588317 -0.757064  0.212836
        0         0         0         1
[ INFO] [1493537679.608907582]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.115444 vs Cam:0.0644161
EE transform: 
 0.846406  0.512564 -0.144481  0.663868
 0.117042  -0.44372  -0.88849 0.0400476
-0.519516  0.735113 -0.435559  0.196143
        0         0         0         1
Cam transform: 
 0.209615  0.217129 -0.953371   0.78508
 0.314646  0.908191   0.27602 -0.149685
 0.925775 -0.357832  0.122051  0.145818
        0         0         0         1
[ INFO] [1493537679.609359233]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.0920312 vs Cam:0.10319
EE transform: 
 0.371265  0.873927 -0.313711  0.582489
-0.671523 0.0193811  -0.74073 -0.110443
-0.641264  0.485671  0.594058  0.210225
        0         0         0         1
Cam transform: 
  0.166593 -0.0606493  -0.984159    0.78221
  -0.50926   0.849387  -0.138548 -0.0283258
  0.844335   0.524274   0.110615   0.162171
         0          0          0          1
[ INFO] [1493537679.609801922]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.078633 vs Cam:0.103478
EE transform: 
 -0.194412   0.897314  -0.396271   0.689605
 -0.903413  -0.321179  -0.284057 -0.0355685
 -0.382163   0.302772   0.873087   0.248729
         0          0          0          1
Cam transform: 
 -0.310953    -0.3317  -0.890665    0.73046
 -0.916208   0.353807   0.188106 -0.0857941
  0.252729   0.874526  -0.413923   0.109739
         0          0          0          1
[ INFO] [1493537679.610244076]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.140734 vs Cam:0.158002
EE transform: 
0.00380638   0.997935 -0.0641172   0.719795
 -0.715418 -0.0420809  -0.697428  -0.115366
 -0.698686  0.0485253   0.713781   0.311563
         0          0          0          1
Cam transform: 
 -0.394316  -0.544214  -0.740504   0.669897
 -0.714264   0.688504  -0.125655 -0.0479955
  0.578223   0.479367  -0.660201  0.0978907
         0          0          0          1
[ INFO] [1493537679.610682751]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.289567 vs Cam:0.235117
EE transform: 
 0.160943  0.808859 -0.565548  0.692687
-0.467261 -0.442286 -0.765539  0.238203
-0.869347  0.387467  0.306765  0.264692
        0         0         0         1
Cam transform: 
-0.429407  0.100189 -0.897537  0.760462
-0.426432  0.853567  0.299298 -0.352083
 0.796094  0.511259 -0.323804   0.14987
        0         0         0         1
[ INFO] [1493537679.611129257]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.0880918 vs Cam:0.0919122
EE transform: 
  0.701298    0.71029 -0.0605818    0.52559
 0.0355382  -0.119712  -0.992172 -0.0362252
 -0.711982   0.693655  -0.109196   0.245273
         0          0          0          1
Cam transform: 
-0.0591548 -0.0404454  -0.997429   0.830807
  0.172508   0.983732 -0.0501209 -0.0909857
   0.98323  -0.175029 -0.0512154    0.25544
         0          0          0          1
[ INFO] [1493537679.611573895]: Hand Eye Calibration Transform Pair Added
L2Norm EE: 0.178307 vs Cam:0.159159
EE transform: 
  0.791774   0.610124 -0.0290322   0.764747
-0.0922811  0.0725003   -0.99309 -0.0815968
 -0.603804   0.788982   0.113707   0.179162
         0          0          0          1
Cam transform: 
  0.121676  -0.217217   -0.96851   0.704562
 0.0926826   0.973983  -0.206801  -0.104441
  0.988233 -0.0646013   0.138643  0.0539669
         0          0          0          1
[handeye_calib_camodocal-1] process has died [pid 27099, exit code -11, cmd /home/yongqi/catkin_ws/devel/lib/handeye_calib_camodocal/handeye_calib_camodocal __name:=handeye_calib_camodocal __log:=/home/yongqi/.ros/log/19d39188-2cb1-11e7-a55b-0c82683d98b6/handeye_calib_camodocal-1.log].
log file: /home/yongqi/.ros/log/19d39188-2cb1-11e7-a55b-0c82683d98b6/handeye_calib_camodocal-1*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete
done

The process died when it runs to

ceres::Solve(options, &problem, &summary); // line 334 in HandEyeCalibration.cc (camodocal library)

About the ros topics

  • Problem Description
    Hello, I am using your ros package to perform hand-eye calibration. In your launch file, there are four ROS topics: ARTagTF, cameraTF,EETF,baseTF. But now I know the transformation from base link to end effector, and the transformation from world to camera, how can I extract four ros topics from these transformation?

How can I estimate the calibrate result?

I have already finish run practice sucessfully. I get the result ,but it can't perform the accuracy error of handeye caliration .The repo will add the funtion about that?

CalibratedTransform.yml matrix elements all zero

hi, I'm running this package's example launch file, and I got almost the same output as the guide. However, I found that the CalibratedTransform.yml file did not record the result. Instead, the elements in the matrix was all approximately zero. Is there anything I'm missing?

Here's my example/CalibratedTransform.yml:

%YAML:1.0
---
ArmTipToMarkerTagTransform: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [ 6.9526708606351848e-310, 2.3341953705113993e-312, 0., 0.,
       4.9406564584124654e-324, 0., 0., 6.9017511077747667e-310,
       6.2252271375997065e-322, 0., 2.3341953705113993e-312,
       2.3715151000379834e-322, 0., 2.6312747813848758e-312, 0.,
       1.0495788289345439e-316 ]

Thanks for your time.

firtEEInverse * eigenEE and firstCamInverse * eigenCam???

fristCamInverse is Tc1m, from tag to fram 1 of cam; eigenCam: Tmc2, from frame 2 of cam to tag; then get Tc1c2; from c2 to c1;

However, firstEEInverse is Tbe1 from ee_fixed_link to base_link; eigenEE; Te2b, from base_link to e2;
What is get Tbe1 * Te2b???

Confuse about the reslut

Great work ! Thanks for sharing.
however in your terminal session the Result shows the tf from /ar_marker_0 to /ee_link:, how ever in the eye-in-hand usage we really care about the tf from /ee_link to /camera_link, any suggestion?

Confusing about A and B

Hi, I find it confusing about generating the desired A and B matrices to feed to this program. Here's several questions:

  1. In the AX=XB slide , A seems to be camera Pose in the upper figure, while in the lower one it seems to be the arm pose. I'm not sure which one is correct? or maybe it doesn't matter?
  2. If the lower one is correct, can I compute A with the equation A = A_j * A_i^(-1) and B = B_j^(-1) * B_i? I know it's a really basic question, but just to make sure if this is correct.
  3. For the input file(TransformPairsInput.yml), T1 is robot pose and T2 is camera pose, right?

I'm rookie to this field, so thanks a lot for your consideration.

Question about the reason to inverse the first pose of robot and fiducial to camera

Hello Hunt, I found you question and solution on robotics.stackexchange.com, and I spend many hours on hand eye calibration, when I try to use your code and look deep in the Ax = xB solution, in the line of your code

here I only caculate with 2 pose
1
and does this the reason why you get the first inverse and then 2nd multiply with inverse, and next 3rd then multiply with the former multiplied results, namely, 3rd_baseHeef * 2nd_baseHeef * inv(1st_baseHeef)? I am not sure about this, and I have seen others use 2nd_baseHeef * inv(1st_baseHeef) = 2nd_camHfiducial * inv(1st_camHfiducial) then 3nd_baseHeef * inv(2st_baseHeef) = 3nd_camHfiducial * inv(2st_camHfiducial), if you know the reason or useful material, I am very appreciate if you can tell me

eye-on-base calibration

Hi,
Can I use this library for eye-on-base calibration? I.e. the camera is static relative to the robot base.
Thanks

Undefined reference to google::FlagRegisterer::FlagRegisterer error

Hi, I am getting this error. I am kind of a noob with Linux, unfortunately, so can someone help me with this error?

Thanks so much!

[ 33%] Linking CXX executable /home/blingshock/me8287_ws/devel/lib/handeye_calib_camodocal/handeye_calib_camodocal
/usr/local/lib/libglog.a(logging.cc.o): In function __static_initialization_and_destruction_0(int, int)': logging.cc:(.text+0x6f7a): undefined reference to google::FlagRegisterer::FlagRegisterer(char const*, char const*, char const*, bool*, bool*)'
logging.cc:(.text+0x7024): undefined reference to google::FlagRegisterer::FlagRegisterer<bool>(char const*, char const*, char const*, bool*, bool*)' logging.cc:(.text+0x70c6): undefined reference to google::FlagRegisterer::FlagRegisterer(char const*, char const*, char const*, bool*, bool*)'
logging.cc:(.text+0x7168): undefined reference to google::FlagRegisterer::FlagRegisterer<bool>(char const*, char const*, char const*, bool*, bool*)' logging.cc:(.text+0x719d): undefined reference to google::FlagRegisterer::FlagRegisterer(char const*, char const*, char const*, int*, int*)'
logging.cc:(.text+0x723a): undefined reference to google::FlagRegisterer::FlagRegisterer<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > >(char const*, char const*, char const*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >*)' logging.cc:(.text+0x7321): undefined reference to google::FlagRegisterer::FlagRegisterer(char const*, char const*, char const*, bool*, bool*)'
logging.cc:(.text+0x73b0): undefined reference to google::FlagRegisterer::FlagRegisterer<int>(char const*, char const*, char const*, int*, int*)' logging.cc:(.text+0x743f): undefined reference to google::FlagRegisterer::FlagRegisterer(char const*, char const*, char const*, int*, int*)'
logging.cc:(.text+0x74ce): undefined reference to google::FlagRegisterer::FlagRegisterer<int>(char const*, char const*, char const*, int*, int*)' logging.cc:(.text+0x755d): undefined reference to google::FlagRegisterer::FlagRegisterer(char const*, char const*, char const*, int*, int*)'
logging.cc:(.text+0x75fa): undefined reference to google::FlagRegisterer::FlagRegisterer<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > >(char const*, char const*, char const*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >*)' logging.cc:(.text+0x76ce): undefined reference to google::FlagRegisterer::FlagRegisterer(char const*, char const*, char const*, int*, int*)'
logging.cc:(.text+0x7769): undefined reference to google::FlagRegisterer::FlagRegisterer<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > >(char const*, char const*, char const*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >*)' logging.cc:(.text+0x784b): undefined reference to google::FlagRegisterer::FlagRegisterer<std::__cxx11::basic_string<char, std::char_traits, std::allocator > >(char const*, char const*, char const*, std::__cxx11::basic_string<char, std::char_traits, std::allocator >, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)'
logging.cc:(.text+0x791f): undefined reference to google::FlagRegisterer::FlagRegisterer<int>(char const*, char const*, char const*, int*, int*)' logging.cc:(.text+0x79c1): undefined reference to google::FlagRegisterer::FlagRegisterer(char const*, char const*, char const*, bool*, bool*)'
logging.cc:(.text+0x7a5e): undefined reference to google::FlagRegisterer::FlagRegisterer<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > >(char const*, char const*, char const*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >*)' /usr/local/lib/libglog.a(utilities.cc.o): In function __static_initialization_and_destruction_0(int, int)':
utilities.cc:(.text+0xae9): undefined reference to google::FlagRegisterer::FlagRegisterer<bool>(char const*, char const*, char const*, bool*, bool*)' /usr/local/lib/libglog.a(vlog_is_on.cc.o): In function __static_initialization_and_destruction_0(int, int)':
vlog_is_on.cc:(.text+0x85c): undefined reference to google::FlagRegisterer::FlagRegisterer<int>(char const*, char const*, char const*, int*, int*)' vlog_is_on.cc:(.text+0x8f9): undefined reference to google::FlagRegisterer::FlagRegisterer<std::__cxx11::basic_string<char, std::char_traits, std::allocator > >(char const*, char const*, char const*, std::__cxx11::basic_string<char, std::char_traits, std::allocator >, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)'
collect2: error: ld returned 1 exit status
handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/build.make:196: recipe for target '/home/blingshock/me8287_ws/devel/lib/handeye_calib_camodocal/handeye_calib_camodocal' failed
make[2]: *** [/home/blingshock/me8287_ws/devel/lib/handeye_calib_camodocal/handeye_calib_camodocal] Error 1
CMakeFiles/Makefile2:591: recipe for target 'handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/all' failed
make[1]: *** [handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

Eigen::JacobiSVD runtime SIGSEGV

Hi while running the calibration i am getting the following segmentation fault. While debugging i learnt that this segmentation fault arising from Eigen. I have already installed eigen3. What can be the reason for such behavior?

Thread 1 "hand_eye_calib" received signal SIGSEGV, Segmentation fault.
0x00007ffff6af2cbc in Eigen::JacobiSVD<Eigen::Matrix<double, -1, -1, 0, -1, -1>, 2>::compute(Eigen::Matrix<double, -1, -1, 0, -1, -1> const&, unsigned int) ()
   from /usr/local/lib/camodocal/libcamodocal_calib.so
(gdb) where
#0  0x00007ffff6af2cbc in Eigen::JacobiSVD<Eigen::Matrix<double, -1, -1, 0, -1, -1>, 2>::compute(Eigen::Matrix<double, -1, -1, 0, -1, -1> const&, unsigned int) () from /usr/local/lib/camodocal/libcamodocal_calib.so
#1  0x00007ffff6adcd7d in camodocal::HandEyeCalibration::estimateHandEyeScrewInitial(Eigen::Matrix<double, -1, -1, 0, -1, -1>&, bool) () from /usr/local/lib/camodocal/libcamodocal_calib.so
#2  0x00007ffff6adde91 in camodocal::HandEyeCalibration::estimateHandEyeScrew(std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::aligned_allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > > const&, std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::aligned_allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > > const&, std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::aligned_allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > > const&, std::vector<Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::aligned_allocator<Eigen::Matrix<double, 3, 1, 0, 3, 1> > > const&, Eigen::Matrix<double, 4, 4, 0, 4, 4>&, bool) () from /usr/local/lib/camodocal/libcamodocal_calib.so
#3  0x00000000004d8919 in estimateHandEye(std::vector<Eigen::Transform<double, 3, 2, 0>, Eigen::aligned_allocator<Eigen::Transform<double, 3, 2, 0> > > const&, std::vector<Eigen::Transform<double, 3, 2, 0>, Eigen::aligned_allocator<Eigen::Transform<double, 3, 2, 0> > > const&) ()
#4  0x00000000004d9129 in estimateHandEye(std::vector<Eigen::Transform<double, 3, 2, 0>, Eigen::aligned_allocator<Eigen::Transform<double, 3, 2, 0> > > const&, std::vector<Eigen::Transform<double, 3, 2, 0>, Eigen::aligned_allocator<Eigen::Transform<double, 3, 2, 0> > > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) ()
#5  0x00000000004dac1b in main ()

cannot find -lgflags_static

Hey, I am trying to get the program running but I can't seem to get it working because of a recurring error that I can't debug, hope you can help me.

~/catkin_ws$ catkin_make

Base path: /home/student/catkin_ws
Source space: /home/student/catkin_ws/src
Build space: /home/student/catkin_ws/build
Devel space: /home/student/catkin_ws/devel
Install space: /home/student/catkin_ws/install

Running command: "make cmake_check_build_system" in "/home/student/catkin_ws/build"

Running command: "make -j8 -l8" in "/home/student/catkin_ws/build"

[ 0%] Built target std_msgs_generate_messages_lisp
[ 0%] Built target std_msgs_generate_messages_nodejs
[ 0%] Built target std_msgs_generate_messages_cpp
[ 0%] Built target std_msgs_generate_messages_eus
[ 0%] Built target std_msgs_generate_messages_py
[ 13%] Built target kinect2_registration
[ 13%] Built target _beginner_tutorials_generate_messages_check_deps_Num
[ 13%] Built target _beginner_tutorials_generate_messages_check_deps_AddTwoInts
[ 16%] Linking CXX executable /home/student/catkin_ws/devel/lib/handeye_calib_camodocal/handeye_calib_camodocal
[ 26%] Built target beginner_tutorials_generate_messages_eus
[ 33%] Built target beginner_tutorials_generate_messages_cpp
[ 40%] Built target beginner_tutorials_generate_messages_lisp
[ 53%] Built target beginner_tutorials_generate_messages_py
[ 60%] Built target kinect2_calibration
[ 66%] Built target kinect2_bridge
[ 73%] Built target kinect2_bridge_nodelet
[ 80%] Built target beginner_tutorials_generate_messages_nodejs
[ 86%] Built target talker
[ 93%] Built target listener
[ 93%] Built target beginner_tutorials_generate_messages
/usr/bin/ld: cannot find -lgflags_static
collect2: error: ld returned 1 exit status
handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/build.make:215: recipe for target '/home/student/catkin_ws/devel/lib/handeye_calib_camodocal/handeye_calib_camodocal' failed
make[2]: *** [/home/student/catkin_ws/devel/lib/handeye_calib_camodocal/handeye_calib_camodocal] Error 1
CMakeFiles/Makefile2:2359: recipe for target 'handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/all' failed
make[1]: *** [handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j8 -l8" failed

pose estimation between moving machine's end effector and the camera mounted on the end effector

@ahundt Hey I have one small doubt. If you can help me with this one then it would be very helpful.
I have one moving machine (consider like robot arm itself, but i have to control it with either matlab or joystick). I have attached one camera to its end effector. I need to do hand eye calibration to estimate the pose between the machine's end effector and the camera mounted on the end effector. I have following things with me.

  1. Pose A: translation (13) and rotation vector (13) between machine's base and machine's end effector, for 32 different positions
  2. Pose B: translation (13) and rotation vector (13) between camera mounted on machine's end effector and diamond charuco (for example https://www.google.com/search?q=diamond+charuco&source=lnms&tbm=isch&sa=X&ved=2ahUKEwjfppa71YzmAhWOaFAKHfrrDK0Q_AUoAXoECAsQAw&biw=1489&bih=787#imgrc=dRBZ_O_LoXFjVM: ), found using opencv, for same 32 different positions (Diamond charuco is placed at fixed location).
    ***Note: I do not have these values in terms of ros message or not saved in rosbag format. My question is, can I use this package to find the pose between end effector and camera mounted on it with the information I have stored.

Camera pose Matrix

Hello,
I'm trying to make a hand eye calibration, but I'm bit stacked! I would like to use the AX=XB method, that, since I understood is the one implemented using comodocal. I read from your presentation the mainly the input for the algorithm are the pose of the robot refers to its base, and the pose of the camera refers to the object ( in my case a chessboard ). Regarding the pose of the camera, I'm computing it using the extrinsic parameters, with this method I get the rotation matrix (unit is radiants )and the traslation matrix (unit is pixel, I guess ). now the problem is that I'm not really sure if this matrix, is the right one for the algorithm.
Could you help me to remove this doubt and clarify the mind ?

undefined reference to `cv::Mat::updateContinuityFlag()' error

Hi, I am getting this error when I run "catkin_make_isolated." I'm not that good with Linux, would anyone be able to help me?

Thanks so much!

==> Processing catkin package: 'handeye_calib_camodocal'
==> Building with env: '/home/blingshock/me8287_ws/devel_isolated/ceres-solver/env.sh'
Makefile exists, skipping explicit cmake invocation...
==> make cmake_check_build_system in '/home/blingshock/me8287_ws/build_isolated/handeye_calib_camodocal'
-- Using CATKIN_DEVEL_PREFIX: /home/blingshock/me8287_ws/devel_isolated/handeye_calib_camodocal
-- Using CMAKE_PREFIX_PATH: /home/blingshock/me8287_ws/devel_isolated/ceres-solver;/opt/ros/kinetic
-- This workspace overlays: /opt/ros/kinetic
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/blingshock/me8287_ws/build_isolated/handeye_calib_camodocal/test_results
-- Found gmock sources under '/usr/src/gmock': gmock will be built
-- Found gtest sources under '/usr/src/gmock': gtests will be built
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.7.14
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- No preference for use of exported gflags CMake configuration set, and no hints for include/library directories provided. Defaulting to preferring an installed/exported gflags CMake configuration if available.
-- Found installed version of gflags: /usr/local/lib/cmake/gflags
-- Detected gflags version: 2.2.0
Gflags found = TRUE
Glog found = TRUE
-- Found installed version of Eigen: /usr/lib/cmake/eigen3
-- Found required Ceres dependency: Eigen version 3.2.92 in /usr/include/eigen3
-- Found installed version of glog: /usr/local/lib/cmake/glog
-- Detected glog version: 0.3.5
-- Found required Ceres dependency: glog
-- Found installed version of gflags: /usr/local/lib/cmake/gflags
-- Detected gflags version: 2.2.0
-- Found required Ceres dependency: gflags
-- Found Ceres version: 1.14.0 installed in: /home/blingshock/me8287_ws/devel_isolated/ceres-solver with components: [EigenSparse, SparseLinearAlgebraLibrary, LAPACK, SuiteSparse, CXSparse, SchurSpecializations, OpenMP, Multithreading]
-- OpenCV version: 3.3.1
-- defined HAVE_OPENCV3
GLOG = glog::glog
-- Configuring done
-- Generating done
-- Build files have been written to: /home/blingshock/me8287_ws/build_isolated/handeye_calib_camodocal
==> make -j4 -l4 in '/home/blingshock/me8287_ws/build_isolated/handeye_calib_camodocal'
[ 33%] Linking CXX executable /home/blingshock/me8287_ws/devel_isolated/handeye_calib_camodocal/lib/handeye_calib_camodocal/handeye_calib_camodocal
CMakeFiles/handeye_calib_camodocal.dir/src/handeye_calibration.cpp.o: In function cv::Mat::Mat(int, int, int, void*, unsigned long)': handeye_calibration.cpp:(.text._ZN2cv3MatC2EiiiPvm[_ZN2cv3MatC5EiiiPvm]+0x2a1): undefined reference to cv::Mat::updateContinuityFlag()'
collect2: error: ld returned 1 exit status
CMakeFiles/handeye_calib_camodocal.dir/build.make:224: recipe for target '/home/blingshock/me8287_ws/devel_isolated/handeye_calib_camodocal/lib/handeye_calib_camodocal/handeye_calib_camodocal' failed
make[2]: *** [/home/blingshock/me8287_ws/devel_isolated/handeye_calib_camodocal/lib/handeye_calib_camodocal/handeye_calib_camodocal] Error 1
CMakeFiles/Makefile2:1091: recipe for target 'CMakeFiles/handeye_calib_camodocal.dir/all' failed
make[1]: *** [CMakeFiles/handeye_calib_camodocal.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
<== Failed to process package 'handeye_calib_camodocal':
Command '['/home/blingshock/me8287_ws/devel_isolated/ceres-solver/env.sh', 'make', '-j4', '-l4']' returned non-zero exit status 2

Reproduce this error by running:
==> cd /home/blingshock/me8287_ws/build_isolated/handeye_calib_camodocal && /home/blingshock/me8287_ws/devel_isolated/ceres-solver/env.sh make -j4 -l4

Command failed, exiting.

cankin_make error

When I run "cankin_make", there is an error that could not find glog, but I can find libglog.so.0.0.0 in /usr/lib, I have installed the package of glog-0.3.4.
`CMake Error at handeye_calib_camodocal-master/CMakeLists.txt:30 (find_package):
By not providing "FindGlog.cmake" in CMAKE_MODULE_PATH this project has
asked CMake to find a package configuration file provided by "Glog", but
CMake did not find one.

Could not find a package configuration file provided by "Glog" with any of
the following names:

GlogConfig.cmake
glog-config.cmake

Add the installation prefix of "Glog" to CMAKE_PREFIX_PATH or set
"Glog_DIR" to a directory containing one of the above files. If "Glog"
provides a separate development package or SDK, be sure it has been
installed.
`

The results before and after refinement are totally different?

In terminal_session.txt, the results before and after refinement are totally different, especially the rotation. I think the two results should be similar. Does anyone know why they are different? @ahundt

# INFO: Before refinement: H_12 =
-0.962926 -0.156063 0.22004 -0.00802514
-0.176531 0.981315 -0.0765322 0.0242905
-0.203985 -0.112539 -0.972484 0.0550756
0 0 0 1

Ceres Solver Report: Iterations: 89, Initial cost: 1.367791e+01, Final cost: 6.005694e-04, Termination: CONVERGENCE
# INFO: After refinement: H_12 =
-0.980558 0.184959 0.0655414 0.00771561
0.0495028 -0.0900424 0.994707 0.0836796
0.189881 0.978613 0.0791359 -0.00867321
0 0 0 1

Result from /ee_link to /ar_marker_0:
-0.980558 0.184959 0.0655414 0.00771561
0.0495028 -0.0900424 0.994707 0.0836796
0.189881 0.978613 0.0791359 -0.00867321
0 0 0 1
Translation (x,y,z) : 0.00771561 0.0836796 -0.00867321
Rotation (w,x,y,z): -0.046193, 0.0871038, 0.672938, 0.733099

Result from /ar_marker_0 to /ee_link:
-0.980558 0.184959 0.0655414 0.00771561
0.0495028 -0.0900424 0.994707 0.0836796
0.189881 0.978613 0.0791359 -0.00867321
0 0 0 1

catkin_make fails

Hi, I cloned your package in my ROS workspace and installed all the dependencies manually.
Now when I am trying to catkin_make workspace it gives me this error.

I am new to ROS and C++, can anyone help me please ?

[ 98%] Built target realsense2_camera
In file included from /usr/local/include/ceres/internal/autodiff.h:151:0,
from /usr/local/include/ceres/autodiff_cost_function.h:130,
from /usr/local/include/ceres/ceres.h:37,
from /home/robotics/software-pickbot/src/handeye_calib_camodocal/./src/camodocal/calib/HandEyeCalibration.h:6,
from /home/robotics/software-pickbot/src/handeye_calib_camodocal/src/camodocal/calib/HandEyeCalibration.cc:1:
/usr/local/include/ceres/jet.h:951:8: error: ‘ScalarBinaryOpTraits’ is not a class template
struct ScalarBinaryOpTraits<ceres::Jet<T, N>, T, BinaryOp> {
^
/usr/local/include/ceres/jet.h:955: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:955:58: note: expected a constant of type ‘int’, got ‘BinaryOp’
In file included from /usr/local/include/ceres/internal/autodiff.h:151:0,
from /usr/local/include/ceres/autodiff_cost_function.h:130,
from /usr/local/include/ceres/ceres.h:37,
from /home/robotics/software-pickbot/src/handeye_calib_camodocal/src/handeye_calibration.cpp:1:
/usr/local/include/ceres/jet.h:951:8: error: ‘ScalarBinaryOpTraits’ is not a class template
struct ScalarBinaryOpTraits<ceres::Jet<T, N>, T, BinaryOp> {
^
/usr/local/include/ceres/jet.h:955: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:955:58: note: expected a constant of type ‘int’, got ‘BinaryOp’
handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/build.make:86: recipe for target 'handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/src/camodocal/calib/HandEyeCalibration.cc.o' failed
make[2]: *** [handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/src/camodocal/calib/HandEyeCalibration.cc.o] Error 1
make[2]: *** Waiting for unfinished jobs....
handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/build.make:62: recipe for target 'handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/src/handeye_calibration.cpp.o' failed
make[2]: *** [handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/src/handeye_calibration.cpp.o] Error 1
CMakeFiles/Makefile2:3958: recipe for target 'handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/all' failed
make[1]: *** [handeye_calib_camodocal/CMakeFiles/handeye_calib_camodocal.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j12 -l12" failed

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.