Calico
A visual-inertial calibration library designed for rapid problem construction and debugging.
Public Member Functions | Static Public Member Functions | Static Public Attributes | List of all members
calico::sensors::UnifiedCameraModel Class Reference

#include <camera_models.h>

Inheritance diagram for calico::sensors::UnifiedCameraModel:
Inheritance graph
[legend]
Collaboration diagram for calico::sensors::UnifiedCameraModel:
Collaboration graph
[legend]

Public Member Functions

UnifiedCameraModeloperator= (const UnifiedCameraModel &)=default
 
CameraIntrinsicsModel GetType () const final
 Getter for camera model type.
 
int NumberOfParameters () const final
 Getter for the number of parameters for this camera model.
 
- Public Member Functions inherited from calico::sensors::CameraModel
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
 

Static Public Member Functions

template<typename T >
static absl::StatusOr< Eigen::Vector2< T > > ProjectPoint (const Eigen::VectorX< T > &intrinsics, const Eigen::Vector3< T > &point)
 
template<typename T >
static absl::StatusOr< Eigen::Vector3< T > > UnprojectPixel (const Eigen::VectorX< T > &intrinsics, const Eigen::Vector2< T > &pixel)
 
- Static Public Member Functions inherited from calico::sensors::CameraModel
static std::unique_ptr< CameraModelCreate (CameraIntrinsicsModel camera_model)
 

Static Public Attributes

static constexpr int kNumberOfParameters = 4
 
static constexpr CameraIntrinsicsModel kModelType = CameraIntrinsicsModel::kUnifiedCamera
 

Detailed Description

Unified camera projection model. This model assumes an isotropic pinhole model, i.e. \(f_x == f_y = f\).
Parameters are in the following order: \([f, c_x, c_y, \alpha]\)

Member Function Documentation

◆ ProjectPoint()

template<typename T >
static absl::StatusOr<Eigen::Vector2<T> > calico::sensors::UnifiedCameraModel::ProjectPoint ( const Eigen::VectorX< T > &  intrinsics,
const Eigen::Vector3< T > &  point 
)
inlinestatic

Returns projection \(\mathbf{p}\), a 2-D pixel coordinate such that

\[ \mathbf{p} = \left[\begin{matrix}f&0\\0&f\end{matrix}\right]\mathbf{p}_d + \left[\begin{matrix}c_x\\c_y\end{matrix}\right]\\ \mathbf{p}_d = s\mathbf{p}_m\\ s = \frac{1}{\alpha d + (1-\alpha)t_z}\\ d = \sqrt{{\mathbf{t}^s_{sx}}^T\mathbf{t}^s_{sx}}\\ \mathbf{p}_m = \left[\begin{matrix}t_x\\t_y\end{matrix}\right] \]

intrinsics is a vector of intrinsics parameters the following order: \([f, c_x, c_y, \xi, \alpha]\)

point is the location of the feature resolved in the camera frame \(\mathbf{t}^s_{sx} = \left[\begin{matrix}t_x&t_y&t_z\end{matrix}\right]^T\).

◆ UnprojectPixel()

template<typename T >
static absl::StatusOr<Eigen::Vector3<T> > calico::sensors::UnifiedCameraModel::UnprojectPixel ( const Eigen::VectorX< T > &  intrinsics,
const Eigen::Vector2< T > &  pixel 
)
inlinestatic

Inverts the projection model \(\mathbf{P}\) to obtain the bearing vector \(\mathbf{p}_m\) of the pixel location \(\mathbf{p}\).

\[ \mathbf{p}_m = \mathbf{p}_s / \|\mathbf{p}_s\|\\ \mathbf{p}_s = s\left[\begin{matrix} m_x\\m_y\\1 \end{matrix}\right] - \left[\begin{matrix} 0\\0\\\xi \end{matrix}\right]\\ s = \frac{\xi + \sqrt{1+(1-\xi^2)r^2}}{1+r^2}\\ r^2 = m_x^2 + m_y^2,\\ m_x = \frac{p_x - c_x}{f}, m_y = \frac{p_y - c_y}{f}\\ \mathbf{p} = \left[\begin{matrix}p_x\\p_y\end{matrix}\right] \]

intrinsics is a vector of intrinsics parameters the following order: \([f, c_x, c_y, \xi, \alpha]\)


The documentation for this class was generated from the following file: