#include <ivt_calibration.h>
Public Member Functions | |
bool | fromCameraInfo (const sensor_msgs::CameraInfo &left, const sensor_msgs::CameraInfo &right) |
Set the camera parameters from the sensor_msgs/CameraInfo messages. More... | |
bool | fromCameraInfo (const sensor_msgs::CameraInfoConstPtr &left, const sensor_msgs::CameraInfoConstPtr &right) |
Set the camera parameters from the sensor_msgs/CameraInfo messages. More... | |
boost::shared_ptr< CStereoCalibration > | getStereoCalibration (bool forRectifiedImages=false) const |
Get the IVT StereoCalibration. More... | |
Private Attributes | |
image_geometry::StereoCameraModel | cam_model |
IVT IvtStereoCalibration class. Conversion between representation of calibration parameters for stereo cameras as ROS message and IVT datastructure.
Definition at line 70 of file ivt_calibration.h.
bool ivt_bridge::IvtStereoCalibration::fromCameraInfo | ( | const sensor_msgs::CameraInfo & | left, |
const sensor_msgs::CameraInfo & | right | ||
) |
Set the camera parameters from the sensor_msgs/CameraInfo messages.
Definition at line 114 of file ivt_calibration.cpp.
bool ivt_bridge::IvtStereoCalibration::fromCameraInfo | ( | const sensor_msgs::CameraInfoConstPtr & | left, |
const sensor_msgs::CameraInfoConstPtr & | right | ||
) |
Set the camera parameters from the sensor_msgs/CameraInfo messages.
Definition at line 118 of file ivt_calibration.cpp.
boost::shared_ptr< CStereoCalibration > ivt_bridge::IvtStereoCalibration::getStereoCalibration | ( | bool | forRectifiedImages = false | ) | const |
Get the IVT StereoCalibration.
forRectifiedImages | If true the calibration will be for rectified images of ros::image_proc, otherwise for a (colored) raw image |
Definition at line 122 of file ivt_calibration.cpp.
|
private |
Definition at line 91 of file ivt_calibration.h.