#include <CameraRGB.h>

Public Types | |
| enum | Source { kVideoFile, kUsbDevice } |
Public Member Functions | |
| CameraVideo (int usbDevice=0, bool rectifyImages=false, float imageRate=0, const Transform &localTransform=Transform::getIdentity()) | |
| CameraVideo (const std::string &filePath, bool rectifyImages=false, float imageRate=0, const Transform &localTransform=Transform::getIdentity()) | |
| const std::string & | getFilePath () const |
| virtual std::string | getSerial () const |
| int | getUsbDevice () const |
| virtual bool | init (const std::string &calibrationFolder=".", const std::string &cameraName="") |
| virtual bool | isCalibrated () const |
| virtual | ~CameraVideo () |
Protected Member Functions | |
| virtual SensorData | captureImage (CameraInfo *info=0) |
Private Attributes | |
| cv::VideoCapture | _capture |
| std::string | _filePath |
| std::string | _guid |
| CameraModel | _model |
| bool | _rectifyImages |
| Source | _src |
| int | _usbDevice |
Definition at line 173 of file CameraRGB.h.
Definition at line 177 of file CameraRGB.h.
| rtabmap::CameraVideo::CameraVideo | ( | int | usbDevice = 0, |
| bool | rectifyImages = false, |
||
| float | imageRate = 0, |
||
| const Transform & | localTransform = Transform::getIdentity() |
||
| ) |
Definition at line 697 of file CameraRGB.cpp.
| rtabmap::CameraVideo::CameraVideo | ( | const std::string & | filePath, |
| bool | rectifyImages = false, |
||
| float | imageRate = 0, |
||
| const Transform & | localTransform = Transform::getIdentity() |
||
| ) |
Definition at line 710 of file CameraRGB.cpp.
| rtabmap::CameraVideo::~CameraVideo | ( | ) | [virtual] |
Definition at line 723 of file CameraRGB.cpp.
| SensorData rtabmap::CameraVideo::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 804 of file CameraRGB.cpp.
| const std::string& rtabmap::CameraVideo::getFilePath | ( | ) | const [inline] |
Definition at line 194 of file CameraRGB.h.
| std::string rtabmap::CameraVideo::getSerial | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 799 of file CameraRGB.cpp.
| int rtabmap::CameraVideo::getUsbDevice | ( | ) | const [inline] |
Definition at line 193 of file CameraRGB.h.
| bool rtabmap::CameraVideo::init | ( | const std::string & | calibrationFolder = ".", |
| const std::string & | cameraName = "" |
||
| ) | [virtual] |
Implements rtabmap::Camera.
Definition at line 728 of file CameraRGB.cpp.
| bool rtabmap::CameraVideo::isCalibrated | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 794 of file CameraRGB.cpp.
cv::VideoCapture rtabmap::CameraVideo::_capture [private] |
Definition at line 204 of file CameraRGB.h.
std::string rtabmap::CameraVideo::_filePath [private] |
Definition at line 201 of file CameraRGB.h.
std::string rtabmap::CameraVideo::_guid [private] |
Definition at line 209 of file CameraRGB.h.
CameraModel rtabmap::CameraVideo::_model [private] |
Definition at line 211 of file CameraRGB.h.
bool rtabmap::CameraVideo::_rectifyImages [private] |
Definition at line 202 of file CameraRGB.h.
Source rtabmap::CameraVideo::_src [private] |
Definition at line 205 of file CameraRGB.h.
int rtabmap::CameraVideo::_usbDevice [private] |
Definition at line 208 of file CameraRGB.h.