#include <CameraStereo.h>
Public Member Functions | |
CameraStereoFlyCapture2 (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 | ~CameraStereoFlyCapture2 () |
Static Public Member Functions | |
static bool | available () |
Protected Member Functions | |
virtual SensorData | captureImage (CameraInfo *info=0) |
Definition at line 83 of file CameraStereo.h.
rtabmap::CameraStereoFlyCapture2::CameraStereoFlyCapture2 | ( | float | imageRate = 0.0f , |
const Transform & | localTransform = Transform::getIdentity() |
||
) |
Definition at line 471 of file CameraStereo.cpp.
Definition at line 484 of file CameraStereo.cpp.
bool rtabmap::CameraStereoFlyCapture2::available | ( | ) | [static] |
Definition at line 498 of file CameraStereo.cpp.
SensorData rtabmap::CameraStereoFlyCapture2::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 625 of file CameraStereo.cpp.
std::string rtabmap::CameraStereoFlyCapture2::getSerial | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 601 of file CameraStereo.cpp.
bool rtabmap::CameraStereoFlyCapture2::init | ( | const std::string & | calibrationFolder = "." , |
const std::string & | cameraName = "" |
||
) | [virtual] |
Implements rtabmap::Camera.
Definition at line 507 of file CameraStereo.cpp.
bool rtabmap::CameraStereoFlyCapture2::isCalibrated | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 586 of file CameraStereo.cpp.