ivt_calibration.h
Go to the documentation of this file.
1 
18 #ifndef IVT_BRIDGE_IVT_CALIBRATION_H
19 #define IVT_BRIDGE_IVT_CALIBRATION_H
20 
21 #include <sensor_msgs/CameraInfo.h>
24 #include <Calibration/Calibration.h>
25 #include <Calibration/StereoCalibration.h>
26 #include <stdexcept>
27 #include <opencv2/core/core.hpp>
28 
29 namespace ivt_bridge {
30 
39 public:
40 
44  bool fromCameraInfo(const sensor_msgs::CameraInfo& msg);
45 
49  bool fromCameraInfo(const sensor_msgs::CameraInfoConstPtr& msg);
50 
56  boost::shared_ptr<CCalibration> getCalibration(bool forRectifiedImages=false) const;
57 
58 
59 private:
61 };
62 
71 public:
72 
76  bool fromCameraInfo(const sensor_msgs::CameraInfo& left, const sensor_msgs::CameraInfo& right);
77 
81  bool fromCameraInfo(const sensor_msgs::CameraInfoConstPtr& left, const sensor_msgs::CameraInfoConstPtr& right);
82 
88  boost::shared_ptr<CStereoCalibration> getStereoCalibration(bool forRectifiedImages=false) const;
89 
90 private:
92 };
93 
94 } // namespace ivt_bridge
95 
96 
97 #endif
image_geometry::PinholeCameraModel cam_model
boost::shared_ptr< CCalibration > getCalibration(bool forRectifiedImages=false) const
Get the IVT Calibration.
image_geometry::StereoCameraModel cam_model
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
Set the camera parameters from the sensor_msgs/CameraInfo messages.


asr_ivt_bridge
Author(s): Hutmacher Robin, Kleinert Daniel, Meißner Pascal
autogenerated on Mon Jun 10 2019 12:39:24