ivt_calibration.h
Go to the documentation of this file.
00001 
00018 #ifndef IVT_BRIDGE_IVT_CALIBRATION_H
00019 #define IVT_BRIDGE_IVT_CALIBRATION_H
00020 
00021 #include <sensor_msgs/CameraInfo.h>
00022 #include <image_geometry/pinhole_camera_model.h>
00023 #include <image_geometry/stereo_camera_model.h>
00024 #include <Calibration/Calibration.h>
00025 #include <Calibration/StereoCalibration.h>
00026 #include <stdexcept>
00027 #include <opencv2/core/core.hpp>
00028 
00029 namespace ivt_bridge {
00030 
00038 class IvtCalibration {
00039 public:
00040 
00044         bool fromCameraInfo(const sensor_msgs::CameraInfo& msg);
00045 
00049         bool fromCameraInfo(const sensor_msgs::CameraInfoConstPtr& msg);
00050 
00056         boost::shared_ptr<CCalibration> getCalibration(bool forRectifiedImages=false) const;
00057 
00058 
00059 private:
00060         image_geometry::PinholeCameraModel cam_model;
00061 };
00062 
00070 class IvtStereoCalibration {
00071 public:
00072 
00076         bool fromCameraInfo(const sensor_msgs::CameraInfo& left, const sensor_msgs::CameraInfo& right);
00077 
00081         bool fromCameraInfo(const sensor_msgs::CameraInfoConstPtr& left, const sensor_msgs::CameraInfoConstPtr& right);
00082 
00088         boost::shared_ptr<CStereoCalibration> getStereoCalibration(bool forRectifiedImages=false) const;
00089     
00090 private:
00091         image_geometry::StereoCameraModel cam_model;
00092 };
00093 
00094 } // namespace ivt_bridge
00095 
00096 
00097 #endif


asr_ivt_bridge
Author(s): Hutmacher Robin, Kleinert Daniel, Meißner Pascal
autogenerated on Sat Jun 8 2019 19:52:36