| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * CalibratedCamera.h | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  *  Created on: Aug 17, 2009 | 
					
						
							|  |  |  |  *      Author: dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #ifndef CalibratedCAMERA_H_
 | 
					
						
							|  |  |  | #define CalibratedCAMERA_H_
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-29 14:54:10 +08:00
										 |  |  | #include "Pose2.h"
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | #include "Pose3.h"
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-12 04:51:03 +08:00
										 |  |  | 	class Point2; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * projects a 3-dimensional point in camera coordinates into the | 
					
						
							|  |  |  | 	 * camera and returns a 2-dimensional point, no calibration applied | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	Point2 project_to_camera(const Point3& cameraPoint); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Derivative of project_to_camera | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	Matrix Dproject_to_camera1(const Point3& cameraPoint); /*2by3 <--*/ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * A Calibrated camera class [R|-R't], calibration K=I. | 
					
						
							|  |  |  | 	 * If calibration is known, it is more computationally efficient | 
					
						
							|  |  |  | 	 * to calibrate the measurements rather than try to predict in pixels. | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	class CalibratedCamera { | 
					
						
							|  |  |  | 	private: | 
					
						
							|  |  |  | 		Pose3 pose_; // 6DOF pose
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	public: | 
					
						
							|  |  |  | 		CalibratedCamera(const Pose3& pose); | 
					
						
							| 
									
										
										
										
											2010-03-05 08:55:36 +08:00
										 |  |  | 		CalibratedCamera(const Vector &v) ; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 		virtual ~CalibratedCamera(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-05 08:55:36 +08:00
										 |  |  | 		inline const Pose3& pose() const {	return pose_; } | 
					
						
							|  |  |  | 		bool equals (const CalibratedCamera &camera, double tol = 1e-9) const { | 
					
						
							|  |  |  | 			return pose_.equals(camera.pose(), tol) ; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 		} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-05 08:55:36 +08:00
										 |  |  | 		inline const CalibratedCamera compose(const CalibratedCamera &c) const { | 
					
						
							|  |  |  | 			return CalibratedCamera( pose_ * c.pose() ) ; | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		inline const CalibratedCamera inverse() const { | 
					
						
							|  |  |  | 			return CalibratedCamera( pose_.inverse() ) ; | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		inline static size_t dim() { return 6 ; } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-29 14:54:10 +08:00
										 |  |  | 		/**
 | 
					
						
							|  |  |  | 		 * Create a level camera at the given 2D pose and height | 
					
						
							| 
									
										
										
										
											2009-09-12 04:51:03 +08:00
										 |  |  | 		 * @param pose2 specifies the location and viewing direction | 
					
						
							|  |  |  | 		 * (theta 0 = looking in direction of positive X axis) | 
					
						
							| 
									
										
										
										
											2009-08-29 14:54:10 +08:00
										 |  |  | 		 */ | 
					
						
							|  |  |  | 		static CalibratedCamera level(const Pose2& pose2, double height); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 		Point2 project(const Point3& P) const; | 
					
						
							|  |  |  | 	}; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/* ************************************************************************* */ | 
					
						
							|  |  |  | 	// measurement functions and derivatives
 | 
					
						
							|  |  |  | 	/* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * This function receives the camera pose and the landmark location and | 
					
						
							| 
									
										
										
										
											2009-10-22 22:44:27 +08:00
										 |  |  | 	 * returns the location the point is supposed to appear in the image | 
					
						
							|  |  |  | 	 * @param camera the CalibratedCamera | 
					
						
							|  |  |  | 	 * @param point a 3D point to be projected | 
					
						
							|  |  |  | 	 * @return the intrinsic coordinates of the projected point | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 	 */ | 
					
						
							|  |  |  | 	Point2 project(const CalibratedCamera& camera, const Point3& point); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							| 
									
										
										
										
											2009-10-22 22:44:27 +08:00
										 |  |  | 	 * Derivatives of project, same paramaters as project | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 	 */ | 
					
						
							|  |  |  | 	Matrix Dproject_pose(const CalibratedCamera& camera, const Point3& point); | 
					
						
							|  |  |  | 	Matrix Dproject_point(const CalibratedCamera& camera, const Point3& point); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * super-duper combined evaluation + derivatives | 
					
						
							|  |  |  | 	 * saves a lot of time because a lot of computation is shared | 
					
						
							| 
									
										
										
										
											2009-10-22 22:44:27 +08:00
										 |  |  | 	 * @return project(camera,point) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 	 */ | 
					
						
							| 
									
										
										
										
											2009-10-22 22:44:27 +08:00
										 |  |  | 	Point2 Dproject_pose_point(const CalibratedCamera& camera, | 
					
						
							|  |  |  | 			const Point3& point, Matrix& D_intrinsic_pose, Matrix& D_intrinsic_point); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #endif /* CalibratedCAMERA_H_ */
 |