00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef CAMERA_H
00025 #define CAMERA_H
00026
00034 #include "Alvar.h"
00035 #include "Pose.h"
00036 #include "Util.h"
00037 #include "FileFormat.h"
00038 #include <vector>
00039
00040 #include <ros/ros.h>
00041 #include <ros/package.h>
00042 #include <ros/console.h>
00043 #include <geometry_msgs/TransformStamped.h>
00044 #include <tf/transform_broadcaster.h>
00045 #include <image_transport/image_transport.h>
00046 #include <sensor_msgs/CameraInfo.h>
00047 #include <visualization_msgs/Marker.h>
00048 #include <resource_retriever/retriever.h>
00049
00050 namespace alvar {
00051
00053 struct ALVAR_EXPORT ProjPoints {
00054 int width;
00055 int height;
00056
00058 std::vector<CvPoint3D64f> object_points;
00065 std::vector<CvPoint2D64f> image_points;
00067 std::vector<int> point_counts;
00068
00070 void Reset();
00071
00073 bool AddPointsUsingChessboard(IplImage *image, double etalon_square_size, int etalon_rows, int etalon_columns, bool visualize);
00074
00076 bool AddPointsUsingMarkers(std::vector<PointDouble> &marker_corners, std::vector<PointDouble> &marker_corners_img, IplImage* image);
00077 };
00078
00079
00083 class ALVAR_EXPORT Camera {
00084
00085 public:
00086
00087 CvMat calib_K; double calib_K_data[3][3];
00088 CvMat calib_D; double calib_D_data[4];
00089 int calib_x_res;
00090 int calib_y_res;
00091 int x_res;
00092 int y_res;
00093 bool getCamInfo_;
00094
00095 protected:
00096 std::string cameraInfoTopic_;
00097 sensor_msgs::CameraInfo cam_info_;
00098 void camInfoCallback (const sensor_msgs::CameraInfoConstPtr &);
00099 ros::Subscriber sub_;
00100 ros::NodeHandle n_;
00101
00102 private:
00103 bool LoadCalibXML(const char *calibfile);
00104 bool LoadCalibOpenCV(const char *calibfile);
00105 bool SaveCalibXML(const char *calibfile);
00106 bool SaveCalibOpenCV(const char *calibfile);
00107
00108 public:
00110 std::string SerializeId() { return "camera"; };
00137 bool Serialize(Serialization *ser) {
00138 if (!ser->Serialize(calib_x_res, "width")) return false;
00139 if (!ser->Serialize(calib_y_res, "height")) return false;
00140 if (!ser->Serialize(calib_K, "intrinsic_matrix")) return false;
00141 if (!ser->Serialize(calib_D, "distortion")) return false;
00142 return true;
00143 }
00144
00146 Camera();
00147 Camera(ros::NodeHandle & n, std::string cam_info_topic);
00148
00150 double GetFovX() {
00151 return (2.0f * atan2(double(x_res) / 2.0f, (double)calib_K_data[0][0]));
00152 }
00154 double GetFovY() {
00155 return (2.0f * atan2(double(y_res) / 2.0f, (double)calib_K_data[1][1]));
00156 }
00157
00158 void SetSimpleCalib(int _x_res, int _y_res, double f_fac=1.);
00159
00166 bool SetCalib(const char *calibfile, int _x_res, int _y_res,
00167 FILE_FORMAT format = FILE_FORMAT_DEFAULT);
00168
00173 bool SaveCalib(const char *calibfile, FILE_FORMAT format = FILE_FORMAT_DEFAULT);
00174
00176 void Calibrate(ProjPoints &pp);
00177
00179 void SetRes(int _x_res, int _y_res);
00180
00200 void GetOpenglProjectionMatrix(double proj_matrix[16], const int width, const int height, const float far_clip = 1000.0f, const float near_clip = 0.1f);
00201
00203 void SetOpenglProjectionMatrix(double proj_matrix[16], const int width, const int height);
00204
00206 void Undistort(std::vector<PointDouble >& points);
00207
00209 void Undistort(PointDouble &point);
00210
00212 void Undistort(CvPoint2D32f& point);
00213
00215 void Distort(CvPoint2D32f& point);
00216
00218 void Distort(std::vector<PointDouble>& points);
00219
00221 void Distort(PointDouble &point);
00222
00224 void CalcExteriorOrientation(std::vector<CvPoint3D64f>& pw, std::vector<CvPoint2D64f>& pi, Pose *pose);
00225
00228 void CalcExteriorOrientation(std::vector<CvPoint3D64f>& pw, std::vector<PointDouble >& pi,
00229 CvMat *rodriques, CvMat *tra);
00230
00233 void CalcExteriorOrientation(std::vector<PointDouble >& pw, std::vector<PointDouble >& pi,
00234 CvMat *rodriques, CvMat *tra);
00235
00238 void CalcExteriorOrientation(std::vector<PointDouble>& pw, std::vector<PointDouble >& pi, Pose *pose);
00239
00241 bool CalcExteriorOrientation(const CvMat* object_points, CvMat* image_points, Pose *pose);
00242
00244 bool CalcExteriorOrientation(const CvMat* object_points, CvMat* image_points, CvMat *rodriques, CvMat *tra);
00245
00247 void ProjectPoint(const CvPoint3D64f pw, const Pose *pose, CvPoint2D64f &pi) const;
00248
00250 void ProjectPoint(const CvPoint3D32f pw, const Pose *pose, CvPoint2D32f &pi) const;
00251
00253 void ProjectPoints(std::vector<CvPoint3D64f>& pw, Pose *pose, std::vector<CvPoint2D64f>& pi) const;
00254
00257 void ProjectPoints(const CvMat* object_points, const CvMat* rotation_vector,
00258 const CvMat* translation_vector, CvMat* image_points) const;
00259
00262 void ProjectPoints(const CvMat* object_points, double gl[16], CvMat* image_points) const;
00263
00265 void ProjectPoints(const CvMat* object_points, const Pose* pose, CvMat* image_points) const;
00266 };
00267
00271 struct ALVAR_EXPORT Homography {
00272 double H_data[3][3];
00273 CvMat H;
00274
00276 Homography();
00277
00279 void Find(const std::vector<PointDouble>& pw, const std::vector<PointDouble>& pi);
00280
00282 void ProjectPoints(const std::vector<PointDouble>& from, std::vector<PointDouble>& to);
00283 };
00284
00285 }
00286
00287 #endif