|
Calico
A visual-inertial calibration library designed for rapid problem construction and debugging.
|
#include <sensor_base.h>

Public Member Functions | |
| virtual absl::Status | UpdateResiduals (ceres::Problem &problem)=0 |
| Update residuals for this sensor. More... | |
| virtual void | ClearResidualInfo ()=0 |
| Clear all stored info about residuals. | |
| virtual void | SetLossFunction (utils::LossFunctionType loss, double scale=1.0)=0 |
| Setter for loss function and scale. | |
| virtual absl::StatusOr< int > | AddParametersToProblem (ceres::Problem &problem)=0 |
| Add this sensor's calibration parameters to the ceres problem. More... | |
| virtual absl::StatusOr< int > | AddResidualsToProblem (ceres::Problem &problem, Trajectory &sensorrig_trajectory, WorldModel &world_model)=0 |
| Contribue this sensor's residuals to the ceres problem. More... | |
| virtual absl::Status | SetMeasurementNoise (double sigma)=0 |
| Set the measurement noise \(\sigma\). More... | |
Base class for sensors. For the sake of readability, we make this a purely virtual class, so setters and getters must be implemented at the derived class level.
|
pure virtual |
Add this sensor's calibration parameters to the ceres problem.
Returns the number of parameters added to the problem, which should be intrinsics + extrinsics + latency. If the sensor's model hasn't been set yet, it will return an invalid argument error.
Implemented in calico::sensors::MultiCamera, calico::sensors::Gyroscope, calico::sensors::Camera, and calico::sensors::Accelerometer.
|
pure virtual |
Contribue this sensor's residuals to the ceres problem.
sensorrig_trajectory is the world-from-sensorrig trajectory \(\mathbf{T}^w_r(t)\).
Implemented in calico::sensors::MultiCamera, calico::sensors::Gyroscope, calico::sensors::Camera, and calico::sensors::Accelerometer.
|
pure virtual |
Set the measurement noise \(\sigma\).
This value is used to weight the sensor's residuals such that:
\[ \boldsymbol{\Sigma} = \sigma^2\mathbf{I}\\ \boldsymbol{\epsilon} = \boldsymbol{\Sigma}^{-1/2}\left(\mathbf{y} - \mathbf{\hat{y}}\left(\mathbf{x}, \boldsymbol{\beta}\right)\right)\\ \mathbf{J} = \frac{\partial\boldsymbol{\epsilon}}{\partial\delta\boldsymbol{\beta}}\\ \delta\boldsymbol{\beta} = \left(\mathbf{J}^T\mathbf{J}\right)^{-1}\mathbf{J}^T\boldsymbol{\epsilon} \]
Implemented in calico::sensors::MultiCamera, calico::sensors::Gyroscope, calico::sensors::Camera, and calico::sensors::Accelerometer.
|
pure virtual |
Update residuals for this sensor.
This will only apply to measurements not marked as outliers.
Note: This method is meant to be invoked by BatchOptimizer ONLY. It is not recommended that you invoke this method manually.
Implemented in calico::sensors::MultiCamera, calico::sensors::Gyroscope, calico::sensors::Camera, and calico::sensors::Accelerometer.