|  | 
| template<typename T > | 
| bool | CalcExteriorOrientation (std::map< int, T > &container, Pose *pose, int type_id=-1) | 
|  | Calculate the pose using the items with matching type_id.  More... 
 | 
|  | 
| template<typename T , typename F > | 
| bool | CalcExteriorOrientation (std::map< int, T > &container, Pose *pose, F do_handle_test) | 
|  | Calculate the pose using the items matching the given functor.  More... 
 | 
|  | 
| template<typename T > | 
| void | Distort (std::map< int, T > &container, int type_id=-1) | 
|  | Distort the items with matching type_id.  More... 
 | 
|  | 
| template<typename T , typename F > | 
| void | Distort (std::map< int, T > &container, F &do_handle_test) | 
|  | Distort the items matching the given functor.  More... 
 | 
|  | 
| template<typename T > | 
| int | EraseUsingReprojectionError (std::map< int, T > &container, float reprojection_error_limit, int type_id=-1, Pose *pose=0) | 
|  | Erases the items matching with type_id having large reprojection error. If type_id == -1 doesn't test the type. If pose is given calls Reproject() internally – otherwise assumes it has been called beforehands.  More... 
 | 
|  | 
| void | Get3dOnDepth (const Pose *pose, CvPoint2D32f p2d, float depth, CvPoint3D32f &p3d) | 
|  | Get 3D-coordinate for 2D feature assuming certain depth.  More... 
 | 
|  | 
| void | Get3dOnPlane (const Pose *pose, CvPoint2D32f p2d, CvPoint3D32f &p3d) | 
|  | Get 3D-coordinate for 2D feature on the plane defined by the pose (z == 0)  More... 
 | 
|  | 
| bool | ReconstructFeature (const Pose *pose1, const Pose *pose2, const CvPoint2D32f *u1, const CvPoint2D32f *u2, CvPoint3D32f *p3d, double limit) | 
|  | Reconstruct 3D point using two camera poses and corresponding undistorted image feature positions.  More... 
 | 
|  | 
| template<typename T > | 
| float | Reproject (std::map< int, T > &container, Pose *pose, int type_id=-1, bool needs_has_p2d=false, bool needs_has_p3d=false, float average_outlier_limit=0.f) | 
|  | Projects p3d in the items matching with type_id into projected_p2d . If type_id == -1 doesn't test the type.  More... 
 | 
|  | 
| template<typename T , typename F > | 
| float | Reproject (std::map< int, T > &container, Pose *pose, F do_handle_test, float average_outlier_limit=0.f) | 
|  | Projects p3d in the items matching with the given functor.  More... 
 | 
|  | 
| template<typename T > | 
| void | Undistort (std::map< int, T > &container, int type_id=-1) | 
|  | Undistort the items with matching type_id.  More... 
 | 
|  | 
| template<typename T , typename F > | 
| void | Undistort (std::map< int, T > &container, F &do_handle_test) | 
|  | Undistort the items matching the given functor.  More... 
 | 
|  | 
| template<typename T > | 
| bool | UpdatePose (std::map< int, T > &container, Pose *pose, int type_id=-1, std::map< int, double > *weights=0) | 
|  | Update the pose using the items with matching type_id.  More... 
 | 
|  | 
| template<typename T , typename F > | 
| bool | UpdatePose (std::map< int, T > &container, Pose *pose, F do_handle_test, std::map< int, double > *weights=0) | 
|  | Update the pose using the items matching the given functor.  More... 
 | 
|  | 
| bool | UpdatePose (const CvMat *object_points, CvMat *image_points, Pose *pose, CvMat *weights=0) | 
|  | Update existing pose based on new observations.  More... 
 | 
|  | 
| bool | UpdatePose (const CvMat *object_points, CvMat *image_points, CvMat *rodriques, CvMat *tra, CvMat *weights=0) | 
|  | Update existing pose (in rodriques&tra) based on new observations.  More... 
 | 
|  | 
| template<typename T > | 
| bool | UpdateRotation (std::map< int, T > &container, Pose *pose, int type_id=-1) | 
|  | Update the rotation in pose using the items with matching type_id.  More... 
 | 
|  | 
| template<typename T , typename F > | 
| bool | UpdateRotation (std::map< int, T > &container, Pose *pose, F do_handle_test) | 
|  | Update the rotation in pose using the items matching the given functor.  More... 
 | 
|  | 
| bool | UpdateRotation (const CvMat *object_points, CvMat *image_points, Pose *pose) | 
|  | Update pose rotations based on new observations.  More... 
 | 
|  | 
| bool | UpdateRotation (const CvMat *object_points, CvMat *image_points, CvMat *rot, CvMat *tra) | 
|  | Update pose rotations (in rodriques&tra) based on new observations.  More... 
 | 
|  | 
| 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... 
 | 
|  |