#include <ivt_calibration.h>
| Public Member Functions | |
| bool | fromCameraInfo (const sensor_msgs::CameraInfo &msg) | 
| Set the camera parameters from the sensor_msgs/CameraInfo messages.  More... | |
| bool | fromCameraInfo (const sensor_msgs::CameraInfoConstPtr &msg) | 
| Set the camera parameters from the sensor_msgs/CameraInfo messages.  More... | |
| boost::shared_ptr< CCalibration > | getCalibration (bool forRectifiedImages=false) const | 
| Get the IVT Calibration.  More... | |
| Private Attributes | |
| image_geometry::PinholeCameraModel | cam_model | 
IVT IvtCalibration class. Conversion between representation of calibration parameters for mono camera as ROS message and IVT datastructure.
Definition at line 38 of file ivt_calibration.h.
| bool ivt_bridge::IvtCalibration::fromCameraInfo | ( | const sensor_msgs::CameraInfo & | msg | ) | 
Set the camera parameters from the sensor_msgs/CameraInfo messages.
Definition at line 102 of file ivt_calibration.cpp.
| bool ivt_bridge::IvtCalibration::fromCameraInfo | ( | const sensor_msgs::CameraInfoConstPtr & | msg | ) | 
Set the camera parameters from the sensor_msgs/CameraInfo messages.
Definition at line 106 of file ivt_calibration.cpp.
| boost::shared_ptr< CCalibration > ivt_bridge::IvtCalibration::getCalibration | ( | bool | forRectifiedImages = false | ) | const | 
Get the IVT Calibration.
| forRectifiedImages | If true the calibration will be for rectified images of ros::image_proc, otherwise for a (colored) raw image | 
Definition at line 110 of file ivt_calibration.cpp.
| 
 | private | 
Definition at line 60 of file ivt_calibration.h.