Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camera. More...
#include <Camera.h>
Public Member Functions | |
void | CalcExteriorOrientation (std::vector< CvPoint3D64f > &pw, std::vector< CvPoint2D64f > &pi, Pose *pose) |
Calculate exterior orientation. | |
void | CalcExteriorOrientation (std::vector< CvPoint3D64f > &pw, std::vector< PointDouble > &pi, CvMat *rodriques, CvMat *tra) |
Calculate exterior orientation. | |
void | CalcExteriorOrientation (std::vector< PointDouble > &pw, std::vector< PointDouble > &pi, CvMat *rodriques, CvMat *tra) |
Calculate exterior orientation. | |
void | CalcExteriorOrientation (std::vector< PointDouble > &pw, std::vector< PointDouble > &pi, Pose *pose) |
Calculate exterior orientation. | |
bool | CalcExteriorOrientation (const CvMat *object_points, CvMat *image_points, Pose *pose) |
Update existing pose based on new observations. Use (CV_32FC3 and CV_32FC2) for matrices. | |
bool | CalcExteriorOrientation (const CvMat *object_points, CvMat *image_points, CvMat *rodriques, CvMat *tra) |
Update existing pose (in rodriques&tra) based on new observations. Use (CV_32FC3 and CV_32FC2) for matrices. | |
void | Calibrate (ProjPoints &pp) |
Calibrate using the collected ProjPoints. | |
Camera () | |
Constructor. | |
Camera (ros::NodeHandle &n, std::string cam_info_topic) | |
void | Distort (CvPoint2D32f &point) |
Applys the lens distortion for one point on an image plane. | |
void | Distort (std::vector< PointDouble > &points) |
Applys the lens distortion for points on image plane. | |
void | Distort (PointDouble &point) |
Applys the lens distortion for points on image plane. | |
double | GetFovX () |
Get x-direction FOV in radians. | |
double | GetFovY () |
Get y-direction FOV in radians. | |
void | GetOpenglProjectionMatrix (double proj_matrix[16], const int width, const int height, const float far_clip=1000.0f, const float near_clip=0.1f) |
Get OpenGL matrix Generates the OpenGL projection matrix based on OpenCV intrinsic camera matrix K. | |
void | ProjectPoint (const CvPoint3D64f pw, const Pose *pose, CvPoint2D64f &pi) const |
Project one point. | |
void | ProjectPoint (const CvPoint3D32f pw, const Pose *pose, CvPoint2D32f &pi) const |
Project one point. | |
void | ProjectPoints (std::vector< CvPoint3D64f > &pw, Pose *pose, std::vector< CvPoint2D64f > &pi) const |
Project points. | |
void | ProjectPoints (const CvMat *object_points, const CvMat *rotation_vector, const CvMat *translation_vector, CvMat *image_points) const |
Project points. | |
void | ProjectPoints (const CvMat *object_points, double gl[16], CvMat *image_points) const |
Project points. | |
void | ProjectPoints (const CvMat *object_points, const Pose *pose, CvMat *image_points) const |
Project points. | |
bool | SaveCalib (const char *calibfile, FILE_FORMAT format=FILE_FORMAT_DEFAULT) |
Save the current calibration information to a file. | |
bool | Serialize (Serialization *ser) |
One of the two methods to make this class serializable by Serialization class. | |
std::string | SerializeId () |
One of the two methods to make this class serializable by Serialization class. | |
bool | SetCalib (const char *calibfile, int _x_res, int _y_res, FILE_FORMAT format=FILE_FORMAT_DEFAULT) |
Set the calibration file and the current resolution for which the calibration is adjusted to. | |
void | SetCameraInfo (const sensor_msgs::CameraInfo &camInfo) |
void | SetOpenglProjectionMatrix (double proj_matrix[16], const int width, const int height) |
Invert operation for GetOpenglProjectionMatrix. | |
void | SetRes (int _x_res, int _y_res) |
If we have no calibration file we can still adjust the default calibration to current resolution. | |
void | SetSimpleCalib (int _x_res, int _y_res, double f_fac=1.) |
void | Undistort (std::vector< PointDouble > &points) |
Unapplys the lens distortion for points on image plane. | |
void | Undistort (PointDouble &point) |
Unapplys the lens distortion for one point on an image plane. | |
void | Undistort (CvPoint2D32f &point) |
Unapplys the lens distortion for one point on an image plane. | |
Public Attributes | |
CvMat | calib_D |
double | calib_D_data [4] |
CvMat | calib_K |
double | calib_K_data [3][3] |
int | calib_x_res |
int | calib_y_res |
bool | getCamInfo_ |
int | x_res |
int | y_res |
Protected Member Functions | |
void | camInfoCallback (const sensor_msgs::CameraInfoConstPtr &) |
Protected Attributes | |
sensor_msgs::CameraInfo | cam_info_ |
std::string | cameraInfoTopic_ |
ros::NodeHandle | n_ |
ros::Subscriber | sub_ |
Private Member Functions | |
bool | LoadCalibOpenCV (const char *calibfile) |
bool | LoadCalibXML (const char *calibfile) |
bool | SaveCalibOpenCV (const char *calibfile) |
bool | SaveCalibXML (const char *calibfile) |
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camera.
Constructor.
Definition at line 106 of file Camera.cpp.
alvar::Camera::Camera | ( | ros::NodeHandle & | n, |
std::string | cam_info_topic | ||
) |
Definition at line 123 of file Camera.cpp.
void alvar::Camera::CalcExteriorOrientation | ( | std::vector< CvPoint3D64f > & | pw, |
std::vector< CvPoint2D64f > & | pi, | ||
Pose * | pose | ||
) |
Calculate exterior orientation.
void alvar::Camera::CalcExteriorOrientation | ( | std::vector< CvPoint3D64f > & | pw, |
std::vector< PointDouble > & | pi, | ||
CvMat * | rodriques, | ||
CvMat * | tra | ||
) |
Calculate exterior orientation.
void alvar::Camera::CalcExteriorOrientation | ( | std::vector< PointDouble > & | pw, |
std::vector< PointDouble > & | pi, | ||
CvMat * | rodriques, | ||
CvMat * | tra | ||
) |
Calculate exterior orientation.
void alvar::Camera::CalcExteriorOrientation | ( | std::vector< PointDouble > & | pw, |
std::vector< PointDouble > & | pi, | ||
Pose * | pose | ||
) |
Calculate exterior orientation.
bool alvar::Camera::CalcExteriorOrientation | ( | const CvMat * | object_points, |
CvMat * | image_points, | ||
Pose * | pose | ||
) |
Update existing pose based on new observations. Use (CV_32FC3 and CV_32FC2) for matrices.
Definition at line 731 of file Camera.cpp.
bool alvar::Camera::CalcExteriorOrientation | ( | const CvMat * | object_points, |
CvMat * | image_points, | ||
CvMat * | rodriques, | ||
CvMat * | tra | ||
) |
Update existing pose (in rodriques&tra) based on new observations. Use (CV_32FC3 and CV_32FC2) for matrices.
Definition at line 726 of file Camera.cpp.
void alvar::Camera::Calibrate | ( | ProjPoints & | pp | ) |
Calibrate using the collected ProjPoints.
Definition at line 351 of file Camera.cpp.
void alvar::Camera::camInfoCallback | ( | const sensor_msgs::CameraInfoConstPtr & | cam_info | ) | [protected] |
Definition at line 260 of file Camera.cpp.
void alvar::Camera::Distort | ( | CvPoint2D32f & | point | ) |
Applys the lens distortion for one point on an image plane.
Definition at line 611 of file Camera.cpp.
void alvar::Camera::Distort | ( | std::vector< PointDouble > & | points | ) |
Applys the lens distortion for points on image plane.
void alvar::Camera::Distort | ( | PointDouble & | point | ) |
Applys the lens distortion for points on image plane.
Definition at line 583 of file Camera.cpp.
double alvar::Camera::GetFovX | ( | ) | [inline] |
double alvar::Camera::GetFovY | ( | ) | [inline] |
void alvar::Camera::GetOpenglProjectionMatrix | ( | double | proj_matrix[16], |
const int | width, | ||
const int | height, | ||
const float | far_clip = 1000.0f , |
||
const float | near_clip = 0.1f |
||
) |
Get OpenGL matrix Generates the OpenGL projection matrix based on OpenCV intrinsic camera matrix K.
2*K[0][0]/width 2*K[0][1]/width -(2*K[0][2]/width+1) 0 0 2*K[1][1]/height 2*K[1][2]/height-1 0 0 0 -(f+n)/(f-n) -2*f*n/(f-n) 0 0 -1 0
Note, that the sign of the element [2][0] is changed. It should be
2*K[0][2]/width+1
The sign change is due to the fact that with OpenCV and OpenGL projection matrices both y and z should be mirrored. With other matrix elements the sign changes eliminate each other, but with principal point in x-direction we need to make the change by hand.
Definition at line 394 of file Camera.cpp.
bool alvar::Camera::LoadCalibOpenCV | ( | const char * | calibfile | ) | [private] |
Definition at line 188 of file Camera.cpp.
bool alvar::Camera::LoadCalibXML | ( | const char * | calibfile | ) | [private] |
Definition at line 176 of file Camera.cpp.
void alvar::Camera::ProjectPoint | ( | const CvPoint3D64f | pw, |
const Pose * | pose, | ||
CvPoint2D64f & | pi | ||
) | const |
Project one point.
Definition at line 814 of file Camera.cpp.
void alvar::Camera::ProjectPoint | ( | const CvPoint3D32f | pw, |
const Pose * | pose, | ||
CvPoint2D32f & | pi | ||
) | const |
Project one point.
Definition at line 824 of file Camera.cpp.
void alvar::Camera::ProjectPoints | ( | std::vector< CvPoint3D64f > & | pw, |
Pose * | pose, | ||
std::vector< CvPoint2D64f > & | pi | ||
) | const |
Project points.
void alvar::Camera::ProjectPoints | ( | const CvMat * | object_points, |
const CvMat * | rotation_vector, | ||
const CvMat * | translation_vector, | ||
CvMat * | image_points | ||
) | const |
Project points.
Definition at line 765 of file Camera.cpp.
void alvar::Camera::ProjectPoints | ( | const CvMat * | object_points, |
double | gl[16], | ||
CvMat * | image_points | ||
) | const |
Project points.
Definition at line 783 of file Camera.cpp.
void alvar::Camera::ProjectPoints | ( | const CvMat * | object_points, |
const Pose * | pose, | ||
CvMat * | image_points | ||
) | const |
Project points.
Definition at line 772 of file Camera.cpp.
bool alvar::Camera::SaveCalib | ( | const char * | calibfile, |
FILE_FORMAT | format = FILE_FORMAT_DEFAULT |
||
) |
Save the current calibration information to a file.
calibfile | File to save. |
format | FILE_FORMAT_OPENCV (default) or FILE_FORMAT_XML (see doc/Camera.xsd). |
Definition at line 336 of file Camera.cpp.
bool alvar::Camera::SaveCalibOpenCV | ( | const char * | calibfile | ) | [private] |
Definition at line 317 of file Camera.cpp.
bool alvar::Camera::SaveCalibXML | ( | const char * | calibfile | ) | [private] |
Definition at line 305 of file Camera.cpp.
bool alvar::Camera::Serialize | ( | Serialization * | ser | ) | [inline] |
One of the two methods to make this class serializable by Serialization class.
You can serialize the Camera class using filename or any std::iostream as follows:
alvar::Camera cam; cam.SetCalib("calib.xml", 320, 240); Serialization sero("calib1.xml"); sero<<cam;
alvar::Camera cam; Serialization seri("calib1.xml"); seri>>cam; cam.SetRes(320, 240);
std::string alvar::Camera::SerializeId | ( | ) | [inline] |
One of the two methods to make this class serializable by Serialization class.
bool alvar::Camera::SetCalib | ( | const char * | calibfile, |
int | _x_res, | ||
int | _y_res, | ||
FILE_FORMAT | format = FILE_FORMAT_DEFAULT |
||
) |
Set the calibration file and the current resolution for which the calibration is adjusted to.
calibfile | File to load. |
_x_res | Width of images captured from the real camera. |
_y_res | Height of images captured from the real camera. |
format | FILE_FORMAT_OPENCV (default) or FILE_FORMAT_XML (see doc/Camera.xsd). |
Definition at line 270 of file Camera.cpp.
void alvar::Camera::SetCameraInfo | ( | const sensor_msgs::CameraInfo & | camInfo | ) |
Sets the intrinsic calibration
Definition at line 228 of file Camera.cpp.
void alvar::Camera::SetOpenglProjectionMatrix | ( | double | proj_matrix[16], |
const int | width, | ||
const int | height | ||
) |
Invert operation for GetOpenglProjectionMatrix.
Definition at line 414 of file Camera.cpp.
void alvar::Camera::SetRes | ( | int | _x_res, |
int | _y_res | ||
) |
If we have no calibration file we can still adjust the default calibration to current resolution.
Definition at line 374 of file Camera.cpp.
void alvar::Camera::SetSimpleCalib | ( | int | _x_res, |
int | _y_res, | ||
double | f_fac = 1. |
||
) |
Definition at line 163 of file Camera.cpp.
void alvar::Camera::Undistort | ( | std::vector< PointDouble > & | points | ) |
Unapplys the lens distortion for points on image plane.
void alvar::Camera::Undistort | ( | PointDouble & | point | ) |
Unapplys the lens distortion for one point on an image plane.
Definition at line 428 of file Camera.cpp.
void alvar::Camera::Undistort | ( | CvPoint2D32f & | point | ) |
Unapplys the lens distortion for one point on an image plane.
Definition at line 491 of file Camera.cpp.
CvMat alvar::Camera::calib_D |
double alvar::Camera::calib_D_data[4] |
CvMat alvar::Camera::calib_K |
double alvar::Camera::calib_K_data[3][3] |
sensor_msgs::CameraInfo alvar::Camera::cam_info_ [protected] |
std::string alvar::Camera::cameraInfoTopic_ [protected] |
ros::NodeHandle alvar::Camera::n_ [protected] |
ros::Subscriber alvar::Camera::sub_ [protected] |