NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
camera::CameraModel Class Reference

#include <camera_model.h>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW CameraModel (const Eigen::Vector3d &position, const Eigen::Matrix3d &rotation, double fov_x, int x_res, int y_res)
 
 CameraModel (const Eigen::Vector3d &position, const Eigen::Matrix3d &rotation, const camera::CameraParameters &params)
 
 CameraModel (const Eigen::Affine3d &transform, const camera::CameraParameters &params)
 
 CameraModel (const camera::CameraParameters &params)
 
 ~CameraModel ()
 
Eigen::Vector2d ImageCoordinates (const Eigen::Vector3d &p) const
 
Eigen::Vector2d ImageCoordinates (double x, double y, double z) const
 
Eigen::Vector3d CameraCoordinates (const Eigen::Vector3d &p) const
 
Eigen::Vector3d CameraCoordinates (double x, double y, double z) const
 
Eigen::Vector3d Ray (int x, int y) const
 
bool IsInFov (const Eigen::Vector3d &p) const
 
bool IsInFov (double x, double y, double z) const
 
double GetFovX (void) const
 
double GetFovY (void) const
 
const camera::CameraParametersGetParameters () const
 
Eigen::Vector3d GetPosition () const
 
Eigen::Matrix3d GetRotation () const
 
const Eigen::Affine3d & GetTransform () const
 
void SetTransform (const Eigen::Affine3d &cam_t_global)
 

Detailed Description

A model of a camera, with transformation matrix and camera parameters.

Constructor & Destructor Documentation

◆ CameraModel() [1/4]

camera::CameraModel::CameraModel ( const Eigen::Vector3d &  position,
const Eigen::Matrix3d &  rotation,
double  fov_x,
int  x_res,
int  y_res 
)

◆ CameraModel() [2/4]

camera::CameraModel::CameraModel ( const Eigen::Vector3d &  position,
const Eigen::Matrix3d &  rotation,
const camera::CameraParameters params 
)

◆ CameraModel() [3/4]

camera::CameraModel::CameraModel ( const Eigen::Affine3d &  transform,
const camera::CameraParameters params 
)

◆ CameraModel() [4/4]

camera::CameraModel::CameraModel ( const camera::CameraParameters params)
explicit

◆ ~CameraModel()

camera::CameraModel::~CameraModel ( )

Member Function Documentation

◆ CameraCoordinates() [1/2]

Eigen::Vector3d camera::CameraModel::CameraCoordinates ( const Eigen::Vector3d &  p) const

◆ CameraCoordinates() [2/2]

Eigen::Vector3d camera::CameraModel::CameraCoordinates ( double  x,
double  y,
double  z 
) const

◆ GetFovX()

double camera::CameraModel::GetFovX ( void  ) const

◆ GetFovY()

double camera::CameraModel::GetFovY ( void  ) const

◆ GetParameters()

const camera::CameraParameters & camera::CameraModel::GetParameters ( ) const

◆ GetPosition()

Eigen::Vector3d camera::CameraModel::GetPosition ( ) const

◆ GetRotation()

Eigen::Matrix3d camera::CameraModel::GetRotation ( ) const

◆ GetTransform()

const Eigen::Affine3d & camera::CameraModel::GetTransform ( ) const

◆ ImageCoordinates() [1/2]

Eigen::Vector2d camera::CameraModel::ImageCoordinates ( const Eigen::Vector3d &  p) const

◆ ImageCoordinates() [2/2]

Eigen::Vector2d camera::CameraModel::ImageCoordinates ( double  x,
double  y,
double  z 
) const

◆ IsInFov() [1/2]

bool camera::CameraModel::IsInFov ( const Eigen::Vector3d &  p) const

◆ IsInFov() [2/2]

bool camera::CameraModel::IsInFov ( double  x,
double  y,
double  z 
) const

◆ Ray()

Eigen::Vector3d camera::CameraModel::Ray ( int  x,
int  y 
) const

◆ SetTransform()

void camera::CameraModel::SetTransform ( const Eigen::Affine3d &  cam_t_global)

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