StereoCameraModel.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef STEREOCAMERAMODEL_H_
00029 #define STEREOCAMERAMODEL_H_
00030 
00031 #include <rtabmap/core/CameraModel.h>
00032 
00033 namespace rtabmap {
00034 
00035 class RTABMAP_EXP StereoCameraModel
00036 {
00037 public:
00038         StereoCameraModel() : leftSuffix_("left"), rightSuffix_("right") {}
00039         StereoCameraModel(
00040                         const std::string & name,
00041                         const cv::Size & imageSize1,
00042                         const cv::Mat & K1, const cv::Mat & D1, const cv::Mat & R1, const cv::Mat & P1,
00043                         const cv::Size & imageSize2,
00044                         const cv::Mat & K2, const cv::Mat & D2, const cv::Mat & R2, const cv::Mat & P2,
00045                         const cv::Mat & R, const cv::Mat & T, const cv::Mat & E, const cv::Mat & F,
00046                         const Transform & localTransform = Transform::getIdentity());
00047 
00048         // if R and T are not null, left and right camera models should be valid to be rectified.
00049         StereoCameraModel(
00050                         const std::string & name,
00051                         const CameraModel & leftCameraModel,
00052                         const CameraModel & rightCameraModel,
00053                         const cv::Mat & R = cv::Mat(),
00054                         const cv::Mat & T = cv::Mat(),
00055                         const cv::Mat & E = cv::Mat(),
00056                         const cv::Mat & F = cv::Mat());
00057         // if extrinsics transform is not null, left and right camera models should be valid to be rectified.
00058         StereoCameraModel(
00059                         const std::string & name,
00060                         const CameraModel & leftCameraModel,
00061                         const CameraModel & rightCameraModel,
00062                         const Transform & extrinsics);
00063 
00064         //minimal
00065         StereoCameraModel(
00066                         double fx,
00067                         double fy,
00068                         double cx,
00069                         double cy,
00070                         double baseline,
00071                         const Transform & localTransform = Transform::getIdentity(),
00072                         const cv::Size & imageSize = cv::Size(0,0));
00073         //minimal to be saved
00074         StereoCameraModel(
00075                         const std::string & name,
00076                         double fx,
00077                         double fy,
00078                         double cx,
00079                         double cy,
00080                         double baseline,
00081                         const Transform & localTransform = Transform::getIdentity(),
00082                         const cv::Size & imageSize = cv::Size(0,0));
00083         virtual ~StereoCameraModel() {}
00084 
00085         bool isValidForProjection() const {return left_.isValidForProjection() && right_.isValidForProjection() && baseline() > 0.0;}
00086         bool isValidForRectification() const {return left_.isValidForRectification() && right_.isValidForRectification();}
00087 
00088         void initRectificationMap() {left_.initRectificationMap(); right_.initRectificationMap();}
00089         bool isRectificationMapInitialized() {return left_.isRectificationMapInitialized() && right_.isRectificationMapInitialized();}
00090 
00091         void setName(const std::string & name, const std::string & leftSuffix = "left", const std::string & rightSuffix = "right");
00092         const std::string & name() const {return name_;}
00093 
00094         // backward compatibility
00095         void setImageSize(const cv::Size & size) {left_.setImageSize(size); right_.setImageSize(size);}
00096 
00097         bool load(const std::string & directory, const std::string & cameraName, bool ignoreStereoTransform = true);
00098         bool save(const std::string & directory, bool ignoreStereoTransform = true) const;
00099         bool saveStereoTransform(const std::string & directory) const;
00100 
00101         double baseline() const {return right_.fx()!=0.0 && left_.fx() != 0.0 ? left_.Tx() / left_.fx() - right_.Tx()/right_.fx():0.0;}
00102 
00103         float computeDepth(float disparity) const;
00104         float computeDisparity(float depth) const; // m
00105         float computeDisparity(unsigned short depth) const; // mm
00106 
00107         const cv::Mat & R() const {return R_;} //extrinsic rotation matrix
00108         const cv::Mat & T() const {return T_;} //extrinsic translation matrix
00109         const cv::Mat & E() const {return E_;} //extrinsic essential matrix
00110         const cv::Mat & F() const {return F_;} //extrinsic fundamental matrix
00111 
00112         void scale(double scale);
00113         void roi(const cv::Rect & roi);
00114 
00115         void setLocalTransform(const Transform & transform) {left_.setLocalTransform(transform);}
00116         const Transform & localTransform() const {return left_.localTransform();}
00117         Transform stereoTransform() const;
00118 
00119         const CameraModel & left() const {return left_;}
00120         const CameraModel & right() const {return right_;}
00121 
00122         const std::string & getLeftSuffix() const {return leftSuffix_;}
00123         const std::string & getRightSuffix() const {return rightSuffix_;}
00124 
00125 private:
00126         std::string leftSuffix_;
00127         std::string rightSuffix_;
00128         CameraModel left_;
00129         CameraModel right_;
00130         std::string name_;
00131         cv::Mat R_;
00132         cv::Mat T_;
00133         cv::Mat E_;
00134         cv::Mat F_;
00135 };
00136 
00137 } // rtabmap
00138 
00139 #endif /* STEREOCAMERAMODEL_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:31