|
Calico
A visual-inertial calibration library designed for rapid problem construction and debugging.
|
Base class for camera models. More...
#include <camera_models.h>

Public Member Functions | |
| template<typename T > | |
| absl::StatusOr< Eigen::Vector2< T > > | ProjectPoint (const Eigen::VectorX< T > &intrinsics, const Eigen::Vector3< T > &point) const |
| template<typename T > | |
| absl::StatusOr< Eigen::Vector3< T > > | UnprojectPixel (const Eigen::VectorX< T > &intrinsics, const Eigen::Vector2< T > &pixel) const |
| virtual CameraIntrinsicsModel | GetType () const =0 |
| Getter for camera model type. | |
| virtual int | NumberOfParameters () const =0 |
| Getter for the number of parameters for this camera model. | |
Static Public Member Functions | |
| static std::unique_ptr< CameraModel > | Create (CameraIntrinsicsModel camera_model) |
Base class for camera models.
|
static |
Factory method for creating a camera model with camera_model type. This method will return a nullptr if an unsupported CameraIntrinsicsModel is passed in.
| absl::StatusOr< Eigen::Vector2< T > > calico::sensors::CameraModel::ProjectPoint | ( | const Eigen::VectorX< T > & | intrinsics, |
| const Eigen::Vector3< T > & | point | ||
| ) | const |
Project a point resolved in the camera frame into the pixel space. Top level call invokes the derived class's implementation.
| absl::StatusOr< Eigen::Vector3< T > > calico::sensors::CameraModel::UnprojectPixel | ( | const Eigen::VectorX< T > & | intrinsics, |
| const Eigen::Vector2< T > & | pixel | ||
| ) | const |
Inverts the projection model \(\mathbf{P}\) to obtain the bearing vector \(\mathbf{p}_m\) of the pixel location \(\mathbf{p}\). Multiplying the return quantity by the distance of the point gives the location of the resolved in the camera frame. Top level call invokes the derived class's implementation.