#include <CameraRGBD.h>
Public Member Functions | |
CameraRealSense2 (const std::string &deviceId="", float imageRate=0, 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 |
void | setEmitterEnabled (bool enabled) |
void | setIRDepthFormat (bool enabled) |
virtual | ~CameraRealSense2 () |
Static Public Member Functions | |
static bool | available () |
Protected Member Functions | |
virtual SensorData | captureImage (CameraInfo *info=0) |
Definition at line 432 of file CameraRGBD.h.
rtabmap::CameraRealSense2::CameraRealSense2 | ( | const std::string & | deviceId = "" , |
float | imageRate = 0 , |
||
const Transform & | localTransform = Transform::getIdentity() |
||
) |
Definition at line 3637 of file CameraRGBD.cpp.
rtabmap::CameraRealSense2::~CameraRealSense2 | ( | ) | [virtual] |
Definition at line 3659 of file CameraRGBD.cpp.
bool rtabmap::CameraRealSense2::available | ( | ) | [static] |
Definition at line 3628 of file CameraRGBD.cpp.
SensorData rtabmap::CameraRealSense2::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 3950 of file CameraRGBD.cpp.
std::string rtabmap::CameraRealSense2::getSerial | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 3928 of file CameraRGBD.cpp.
bool rtabmap::CameraRealSense2::init | ( | const std::string & | calibrationFolder = "." , |
const std::string & | cameraName = "" |
||
) | [virtual] |
Implements rtabmap::Camera.
Definition at line 3744 of file CameraRGBD.cpp.
bool rtabmap::CameraRealSense2::isCalibrated | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 3923 of file CameraRGBD.cpp.
void rtabmap::CameraRealSense2::setEmitterEnabled | ( | bool | enabled | ) |
Definition at line 3936 of file CameraRGBD.cpp.
void rtabmap::CameraRealSense2::setIRDepthFormat | ( | bool | enabled | ) |
Definition at line 3943 of file CameraRGBD.cpp.