-
Notifications
You must be signed in to change notification settings - Fork 15
Home
Calico is a lightweight visual-inertial calibration library that allows for rapid problem construction, debugging, and tool creation. Unlike other codebases that are limited to standalone calibration tools for specific hardware setups, Calico is a flexible library that enables building and modifying custom tools to suit your hardware requirements. If your calibration problem aligns with our geometry paradigm, there is no need to modify the underlying optimization.
Calico features:
- Flexible auto-differentiable cost functors.
- Sensor intrinsics, extrinsics, and latency estimation.
- The ability to add multiple sensors.
- Measurement outlier tagging and exclusion.
- Per-sensor robustifier kernels.
- Ability to create custom sensor models.
Calico currently supports cameras, gyroscopes, and accelerometers.
At its core, Calico is a camera-centric library with support for many common camera models including:
- OpenCV's 5-parameter rad-tan model
- OpenCV's 8-parameter rad-tan model
- Kannala-Brandt model
- Double Sphere model
- Field of View model
- Unified camera model
- Extended unified camera model
- Head to the Installation page to install the library.
- Check out some example calibration workflows on our Demos page.
- Review the API.
- Once you feel comfortable with the library, you can start building tools yourself.
What does Calico code look like?
Calico makes building and rebuilding optimization problems fast and easy. Here's what an application for calibrating a stereo-camera plus IMU system might resemble:
from calico import Camera, Accelerometer, Gyroscope
from calico import Trajectory, WorldModel
from calico import BatchOptimizer, SolverOptions, LossFunctionType
# Initialize all sensors and optimization objects.
trajectory, world_model = Trajectory(), WorldModel()
camera_left, camera_right, accel, gyro = Camera(), Camera(), Acceleometer(), Gyroscope(),
...some initialization code...
# Calibrate stereo pair first.
camera_left.SetLossFunction(LossFunctionType.kCauchy, scale=1.0) # Enable robust optimization.
camera_right.SetLossFunction(LossFunctionType.kCauchy, scale=1.0)
camera_left.EnableIntrinsicsEstimation(True)
camera_right.EnableIntrinsicsEstimation(True)
camera_right.EnableExtrinsicsEstimation(True)
camera_right.EnableLatencyEstimation(True)
optimizer = BatchOptimizer()
optimizer.AddTrajectory(trajectory)
optimizer.AddWorldModel(world_model)
optimizer.AddSensor(camera_left)
optimizer.AddSensor(camera_right)
summary = optimizer.Optimize()
print(summary.FullReport())
# Remove some outliers.
kOutlierThreshold = 25
ids_to_remove_left = list()
for measurement, residual in camera_left.GetMeasurementResidualPairs():
if np.linalg.norm(residual) > kOutlierThreshold:
ids_to_remove_left.append(measurement.id)
camera_left.MarkOutliersById(ids_to_remove_left)
# Refine camera intrinsics/extrinsics optimization with outliers excluded.
options = SovlerOptions()
options.minimizer_progress_to_stdout = True # Verbose minimizer iterations
options.num_threads = 4 # multi-threaded normal equation solving
summary = optimizer.Optimize(options)
# Add IMU into the mix with camera parameters fixed.
camera_left.EnableIntrinsicsEstimation(False)
camera_right.EnableExtrinsicsEstimation(False)
camera_right.EnableIntrinsicsEstimation(False)
camera_right.EnableLatencyEstimation(False)
accel.EnableIntrinsicsEstimation(True)
accel.EnableExtrinsicsEstimation(True)
accel.EnableLatencyEstimation(True)
gyro.EnableIntrinsicsEstimation(True)
gyro.EnableExtrinsicsEstimation(True)
gyro.EnableLatencyEstimation(True)
optimizer.AddSensor(accel)
optimizer.AddSensor(gyro)
summary = optimizer.Optimize(options)If you use this repository for research, please add the following citation:
@Misc{Yang2023Calico,
author = {James Yang},
title = {Calico - A visual-inertial calibration library designed for rapid problem construction and debugging.},
howpublished = {Github},
year = {2023},
url = {https://github.com/yangjames/Calico}
}
Keep up to date with upcoming features and projects.
Found a bug? Please help by creating an issue!
Want to contribute? Feel free to put in a pull request, or send an email to calico.github@gmail.com.
I'd like to thank Dr. Gus Lott for teaching me the nuances of least-squares optimization, bundle adjustment, and the