#include <CameraStereo.h>

Public Member Functions | |
| CameraStereoZed (int deviceId, int resolution=2, int quality=1, int sensingMode=0, int confidenceThr=100, bool computeOdometry=false, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity(), bool selfCalibration=true) | |
| CameraStereoZed (const std::string &svoFilePath, int quality=1, int sensingMode=0, int confidenceThr=100, bool computeOdometry=false, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity(), bool selfCalibration=true) | |
| virtual std::string | getSerial () const |
| virtual bool | init (const std::string &calibrationFolder=".", const std::string &cameraName="") |
| virtual bool | isCalibrated () const |
| virtual bool | odomProvided () const |
| virtual | ~CameraStereoZed () |
Static Public Member Functions | |
| static bool | available () |
Protected Member Functions | |
| virtual SensorData | captureImage (CameraInfo *info=0) |
Definition at line 110 of file CameraStereo.h.
| rtabmap::CameraStereoZed::CameraStereoZed | ( | int | deviceId, |
| int | resolution = 2, |
||
| int | quality = 1, |
||
| int | sensingMode = 0, |
||
| int | confidenceThr = 100, |
||
| bool | computeOdometry = false, |
||
| float | imageRate = 0.0f, |
||
| const Transform & | localTransform = Transform::getIdentity(), |
||
| bool | selfCalibration = true |
||
| ) |
Definition at line 762 of file CameraStereo.cpp.
| rtabmap::CameraStereoZed::CameraStereoZed | ( | const std::string & | svoFilePath, |
| int | quality = 1, |
||
| int | sensingMode = 0, |
||
| int | confidenceThr = 100, |
||
| bool | computeOdometry = false, |
||
| float | imageRate = 0.0f, |
||
| const Transform & | localTransform = Transform::getIdentity(), |
||
| bool | selfCalibration = true |
||
| ) |
Definition at line 797 of file CameraStereo.cpp.
| rtabmap::CameraStereoZed::~CameraStereoZed | ( | ) | [virtual] |
Definition at line 831 of file CameraStereo.cpp.
| bool rtabmap::CameraStereoZed::available | ( | ) | [static] |
Definition at line 753 of file CameraStereo.cpp.
| SensorData rtabmap::CameraStereoZed::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 993 of file CameraStereo.cpp.
| std::string rtabmap::CameraStereoZed::getSerial | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 945 of file CameraStereo.cpp.
| bool rtabmap::CameraStereoZed::init | ( | const std::string & | calibrationFolder = ".", |
| const std::string & | cameraName = "" |
||
| ) | [virtual] |
Implements rtabmap::Camera.
Definition at line 838 of file CameraStereo.cpp.
| bool rtabmap::CameraStereoZed::isCalibrated | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 936 of file CameraStereo.cpp.
| bool rtabmap::CameraStereoZed::odomProvided | ( | ) | const [virtual] |
Reimplemented from rtabmap::Camera.
Definition at line 956 of file CameraStereo.cpp.