GA_MultiRobot
Calibrate Multi-Robot with Geometric Algebra (GA) and Geometric Calculus (GC). More specifically the
Problem Formulation
As an updated version of hand-eye calibration,
Folder Structure
- utils: fundamental functions such as basic GA calculation, robot kinematics, and GA robot kinematics.
- project_utils: the
DualRobotCalibrator
solver, which includes all the solver functions from the article and the reproduced version of other researchers' algorithms. - Benchmark: the benchmark code for the proposed method and other algorithms.
- Experiments: scripts related to experimental pose generation, raw data (point cloud) processing, and final benchmarking.
- images: This folder contains all the saved results.
- test: some test scripts.
Each folder has its own README.md for detailed illustration.
Installation:
You need to install Julia
and Matlab
ahead to run this package. We recommend julia>1.8.1 < 1.9
and MATLAB>2022b
for best performance and visualization.
- You need to enter the folder in your terminal by
cd GA_MultiRobot
(or whatever you name the folder) dir
(windows) orls
(linux), and you should see all folder names andProject.toml
,Manifest.toml
- Activate and setup the project environment for
julia
julia> ]
(@v1.8) pkg> activate .
(GA_MultiRobot) pkg> instantiate # This may take long depending on your network condition
Demo
Run the demo with the following command:
julia --project=. -O3 demo.jl
It may take a while for plotting, which is a known issue for Julia and will be fixed in v1.9.x.
The result will be saved at ./Assets/demo.svg
. Noted that the result marked by "GA" is the unpublished version of the proposed method, which is based on Projective Geometric Algebra (PGA). The published version is based on
Highlights
High accuracy
Result in a measurement experiment. The proposed GA-based method reached identical optimal accuracy as Wang's (SOTA) and Wu's method, and higher accuracy than Fu's and Ma's method.
High Efficiency
Execution Time | Flops |
---|---|
![]() |
![]() |
The proposed method solves the problem ~4.5x faster with ~3.5x less computational load than SOTA.
Benchmark
Read Benchmark.md for detailed benchmark.
Related Methods
- Wang's method (previous SOTA): Simultaneous calibration of multicoordinates for a dual-robot system by solving the AXB = YCZ problem
- Wu's method (previous SOTA): Simultaneous Hand-Eye, Tool-Flange, and Robot-Robot Calibration for Comanipulation by Solving the AXB = YCZ Problem
- Fu's Method (A method based on Dual-quaternion): A Dual Quaternion-Based Approach for Coordinate Calibration of Dual Robots in Collaborative Motion
- Ma's Method (temporal info free): Probabilistic approaches to the AXB= YCZ calibration problem in multi-robot systems
- Bayro's AX=XB Method: Motor algebra for 3D kinematics: the case of the hand-eye calibration
Cite this work
@ARTICLE{10215071,
author={Sui, Sizhe and Ding, Ye},
journal={IEEE Transactions on Automation Science and Engineering},
title={Solving the AXB=YCZ Problem for a Dual-Robot System With Geometric Calculus},
year={2023},
volume={},
number={},
pages={1-19},
doi={10.1109/TASE.2023.3299969}}
An open-sourced version of this article can be found on the Author's Researchgate.
TODO
- Upload Simulation Benchmark Code
- Upload Experiment Data & Benchmark Code
- Upload Experiment Video
- Port project to C++ for better usability and efficiency