#include <CameraStereo.h>
Public Member Functions | |
CameraStereoImages (const std::string &pathLeftImages, const std::string &pathRightImages, bool rectifyImages=false, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity()) | |
CameraStereoImages (const std::string &pathLeftRightImages, 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 | ~CameraStereoImages () |
Static Public Member Functions | |
static bool | available () |
Protected Member Functions | |
virtual SensorData | captureImage (CameraInfo *info=0) |
Private Attributes | |
CameraImages * | camera2_ |
StereoCameraModel | stereoModel_ |
Definition at line 160 of file CameraStereo.h.
rtabmap::CameraStereoImages::CameraStereoImages | ( | const std::string & | pathLeftImages, |
const std::string & | pathRightImages, | ||
bool | rectifyImages = false , |
||
float | imageRate = 0.0f , |
||
const Transform & | localTransform = Transform::getIdentity() |
||
) |
Definition at line 1006 of file CameraStereo.cpp.
rtabmap::CameraStereoImages::CameraStereoImages | ( | const std::string & | pathLeftRightImages, |
bool | rectifyImages = false , |
||
float | imageRate = 0.0f , |
||
const Transform & | localTransform = Transform::getIdentity() |
||
) |
Definition at line 1018 of file CameraStereo.cpp.
rtabmap::CameraStereoImages::~CameraStereoImages | ( | ) | [virtual] |
Definition at line 1043 of file CameraStereo.cpp.
bool rtabmap::CameraStereoImages::available | ( | ) | [static] |
Definition at line 1001 of file CameraStereo.cpp.
SensorData rtabmap::CameraStereoImages::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 1127 of file CameraStereo.cpp.
std::string rtabmap::CameraStereoImages::getSerial | ( | ) | const [virtual] |
Reimplemented from rtabmap::CameraImages.
Definition at line 1122 of file CameraStereo.cpp.
bool rtabmap::CameraStereoImages::init | ( | const std::string & | calibrationFolder = "." , |
const std::string & | cameraName = "" |
||
) | [virtual] |
Reimplemented from rtabmap::CameraImages.
Definition at line 1053 of file CameraStereo.cpp.
bool rtabmap::CameraStereoImages::isCalibrated | ( | ) | const [virtual] |
Reimplemented from rtabmap::CameraImages.
Definition at line 1117 of file CameraStereo.cpp.
Definition at line 188 of file CameraStereo.h.
Definition at line 189 of file CameraStereo.h.