#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 197 of file CameraRGB.h.
Definition at line 201 of file CameraRGB.h.
rtabmap::CameraVideo::CameraVideo | ( | int | usbDevice = 0 , |
bool | rectifyImages = false , |
||
float | imageRate = 0 , |
||
const Transform & | localTransform = Transform::getIdentity() |
||
) |
Definition at line 784 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 797 of file CameraRGB.cpp.
rtabmap::CameraVideo::~CameraVideo | ( | ) | [virtual] |
Definition at line 810 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 891 of file CameraRGB.cpp.
const std::string& rtabmap::CameraVideo::getFilePath | ( | ) | const [inline] |
Definition at line 218 of file CameraRGB.h.
std::string rtabmap::CameraVideo::getSerial | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 886 of file CameraRGB.cpp.
int rtabmap::CameraVideo::getUsbDevice | ( | ) | const [inline] |
Definition at line 217 of file CameraRGB.h.
bool rtabmap::CameraVideo::init | ( | const std::string & | calibrationFolder = "." , |
const std::string & | cameraName = "" |
||
) | [virtual] |
Implements rtabmap::Camera.
Definition at line 815 of file CameraRGB.cpp.
bool rtabmap::CameraVideo::isCalibrated | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 881 of file CameraRGB.cpp.
cv::VideoCapture rtabmap::CameraVideo::_capture [private] |
Definition at line 228 of file CameraRGB.h.
std::string rtabmap::CameraVideo::_filePath [private] |
Definition at line 225 of file CameraRGB.h.
std::string rtabmap::CameraVideo::_guid [private] |
Definition at line 233 of file CameraRGB.h.
CameraModel rtabmap::CameraVideo::_model [private] |
Definition at line 235 of file CameraRGB.h.
bool rtabmap::CameraVideo::_rectifyImages [private] |
Definition at line 226 of file CameraRGB.h.
Source rtabmap::CameraVideo::_src [private] |
Definition at line 229 of file CameraRGB.h.
int rtabmap::CameraVideo::_usbDevice [private] |
Definition at line 232 of file CameraRGB.h.