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.  More... | |
| void | CalcExteriorOrientation (std::vector< CvPoint3D64f > &pw, std::vector< PointDouble > &pi, CvMat *rodriques, CvMat *tra) | 
| Calculate exterior orientation.  More... | |
| void | CalcExteriorOrientation (std::vector< PointDouble > &pw, std::vector< PointDouble > &pi, CvMat *rodriques, CvMat *tra) | 
| Calculate exterior orientation.  More... | |
| void | CalcExteriorOrientation (std::vector< PointDouble > &pw, std::vector< PointDouble > &pi, Pose *pose) | 
| Calculate exterior orientation.  More... | |
| 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.  More... | |
| 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.  More... | |
| void | Calibrate (ProjPoints &pp) | 
| Calibrate using the collected ProjPoints.  More... | |
| Camera () | |
| Constructor.  More... | |
| Camera (ros::NodeHandle &n, std::string cam_info_topic) | |
| void | Distort (CvPoint2D32f &point) | 
| Applys the lens distortion for one point on an image plane.  More... | |
| void | Distort (std::vector< PointDouble > &points) | 
| Applys the lens distortion for points on image plane.  More... | |
| void | Distort (PointDouble &point) | 
| Applys the lens distortion for points on image plane.  More... | |
| double | GetFovX () | 
| Get x-direction FOV in radians.  More... | |
| double | GetFovY () | 
| Get y-direction FOV in radians.  More... | |
| 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.  More... | |
| void | ProjectPoint (const CvPoint3D64f pw, const Pose *pose, CvPoint2D64f &pi) const | 
| Project one point.  More... | |
| void | ProjectPoint (const CvPoint3D32f pw, const Pose *pose, CvPoint2D32f &pi) const | 
| Project one point.  More... | |
| void | ProjectPoints (std::vector< CvPoint3D64f > &pw, Pose *pose, std::vector< CvPoint2D64f > &pi) const | 
| Project points.  More... | |
| void | ProjectPoints (const CvMat *object_points, const CvMat *rotation_vector, const CvMat *translation_vector, CvMat *image_points) const | 
| Project points.  More... | |
| void | ProjectPoints (const CvMat *object_points, double gl[16], CvMat *image_points) const | 
| Project points.  More... | |
| void | ProjectPoints (const CvMat *object_points, const Pose *pose, CvMat *image_points) const | 
| Project points.  More... | |
| bool | SaveCalib (const char *calibfile, FILE_FORMAT format=FILE_FORMAT_DEFAULT) | 
| Save the current calibration information to a file.  More... | |
| bool | Serialize (Serialization *ser) | 
| One of the two methods to make this class serializable by Serialization class.  More... | |
| std::string | SerializeId () | 
| One of the two methods to make this class serializable by Serialization class.  More... | |
| 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.  More... | |
| void | SetCameraInfo (const sensor_msgs::CameraInfo &camInfo) | 
| void | SetOpenglProjectionMatrix (double proj_matrix[16], const int width, const int height) | 
| Invert operation for GetOpenglProjectionMatrix.  More... | |
| void | SetRes (int _x_res, int _y_res) | 
| If we have no calibration file we can still adjust the default calibration to current resolution.  More... | |
| 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.  More... | |
| void | Undistort (PointDouble &point) | 
| Unapplys the lens distortion for one point on an image plane.  More... | |
| void | Undistort (CvPoint2D32f &point) | 
| Unapplys the lens distortion for one point on an image plane.  More... | |
| 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.
| alvar::Camera::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.
| 
 | 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.
| 
 | inline | 
| 
 | 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.
Note, that the sign of the element [2][0] is changed. It should be
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.
| 
 | private | 
Definition at line 188 of file Camera.cpp.
| 
 | 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.
| 
 | private | 
Definition at line 317 of file Camera.cpp.
| 
 | private | 
Definition at line 305 of file Camera.cpp.
| 
 | 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:
| 
 | 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.
| 
 | protected | 
| 
 | protected |