#include <CameraStereo.h>

Public Member Functions | |
| CameraStereoVideo (const std::string &path, bool rectifyImages=false, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity()) | |
| CameraStereoVideo (int device, bool rectifyImages=false, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity()) | |
| virtual std::string | getSerial () const |
| virtual bool | init (const std::string &calibrationFolder=".", const std::string &cameraName="") |
| virtual bool | isCalibrated () const |
| virtual | ~CameraStereoVideo () |
Static Public Member Functions | |
| static bool | available () |
Protected Member Functions | |
| virtual SensorData | captureImage (CameraInfo *info=0) |
Private Attributes | |
| std::string | cameraName_ |
| cv::VideoCapture | capture_ |
| std::string | path_ |
| bool | rectifyImages_ |
| CameraVideo::Source | src_ |
| StereoCameraModel | stereoModel_ |
| int | usbDevice_ |
Definition at line 197 of file CameraStereo.h.
| rtabmap::CameraStereoVideo::CameraStereoVideo | ( | const std::string & | path, |
| bool | rectifyImages = false, |
||
| float | imageRate = 0.0f, |
||
| const Transform & | localTransform = Transform::getIdentity() |
||
| ) |
Definition at line 1181 of file CameraStereo.cpp.
| rtabmap::CameraStereoVideo::CameraStereoVideo | ( | int | device, |
| bool | rectifyImages = false, |
||
| float | imageRate = 0.0f, |
||
| const Transform & | localTransform = Transform::getIdentity() |
||
| ) |
Definition at line 1194 of file CameraStereo.cpp.
| rtabmap::CameraStereoVideo::~CameraStereoVideo | ( | ) | [virtual] |
Definition at line 1207 of file CameraStereo.cpp.
| bool rtabmap::CameraStereoVideo::available | ( | ) | [static] |
Definition at line 1176 of file CameraStereo.cpp.
| SensorData rtabmap::CameraStereoVideo::captureImage | ( | CameraInfo * | info = 0 | ) | [protected, virtual] |
returned rgb and depth images should be already rectified if calibration was loaded
Implements rtabmap::Camera.
Definition at line 1290 of file CameraStereo.cpp.
| std::string rtabmap::CameraStereoVideo::getSerial | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 1285 of file CameraStereo.cpp.
| bool rtabmap::CameraStereoVideo::init | ( | const std::string & | calibrationFolder = ".", |
| const std::string & | cameraName = "" |
||
| ) | [virtual] |
Implements rtabmap::Camera.
Definition at line 1212 of file CameraStereo.cpp.
| bool rtabmap::CameraStereoVideo::isCalibrated | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 1280 of file CameraStereo.cpp.
std::string rtabmap::CameraStereoVideo::cameraName_ [private] |
Definition at line 228 of file CameraStereo.h.
cv::VideoCapture rtabmap::CameraStereoVideo::capture_ [private] |
Definition at line 224 of file CameraStereo.h.
std::string rtabmap::CameraStereoVideo::path_ [private] |
Definition at line 225 of file CameraStereo.h.
bool rtabmap::CameraStereoVideo::rectifyImages_ [private] |
Definition at line 226 of file CameraStereo.h.
Definition at line 229 of file CameraStereo.h.
Definition at line 227 of file CameraStereo.h.
int rtabmap::CameraStereoVideo::usbDevice_ [private] |
Definition at line 230 of file CameraStereo.h.