#include <CameraRGBD.h>
Public Member Functions | |
CameraRGBDImages (const std::string &pathRGBImages, const std::string &pathDepthImages, float depthScaleFactor=1.0f, 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 void | setStartIndex (int index) |
virtual | ~CameraRGBDImages () |
Static Public Member Functions | |
static bool | available () |
Protected Member Functions | |
virtual SensorData | captureImage (CameraInfo *info=0) |
Private Attributes | |
CameraImages | cameraDepth_ |
Definition at line 481 of file CameraRGBD.h.
rtabmap::CameraRGBDImages::CameraRGBDImages | ( | const std::string & | pathRGBImages, |
const std::string & | pathDepthImages, | ||
float | depthScaleFactor = 1.0f , |
||
float | imageRate = 0.0f , |
||
const Transform & | localTransform = Transform::getIdentity() |
||
) |
Definition at line 4044 of file CameraRGBD.cpp.
rtabmap::CameraRGBDImages::~CameraRGBDImages | ( | ) | [virtual] |
Definition at line 4057 of file CameraRGBD.cpp.
bool rtabmap::CameraRGBDImages::available | ( | ) | [static] |
Definition at line 4039 of file CameraRGBD.cpp.
SensorData rtabmap::CameraRGBDImages::captureImage | ( | CameraInfo * | info = 0 | ) | [protected, virtual] |
returned rgb and depth images should be already rectified if calibration was loaded
Reimplemented from rtabmap::CameraImages.
Definition at line 4090 of file CameraRGBD.cpp.
std::string rtabmap::CameraRGBDImages::getSerial | ( | ) | const [virtual] |
Reimplemented from rtabmap::CameraImages.
Definition at line 4085 of file CameraRGBD.cpp.
bool rtabmap::CameraRGBDImages::init | ( | const std::string & | calibrationFolder = "." , |
const std::string & | cameraName = "" |
||
) | [virtual] |
Reimplemented from rtabmap::CameraImages.
Definition at line 4061 of file CameraRGBD.cpp.
bool rtabmap::CameraRGBDImages::isCalibrated | ( | ) | const [virtual] |
Reimplemented from rtabmap::CameraImages.
Definition at line 4080 of file CameraRGBD.cpp.
virtual void rtabmap::CameraRGBDImages::setStartIndex | ( | int | index | ) | [inline, virtual] |
Reimplemented from rtabmap::CameraImages.
Definition at line 500 of file CameraRGBD.h.
Definition at line 506 of file CameraRGBD.h.