#include <CameraRGBD.h>

Public Member Functions | |
| CameraOpenni (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 |
| virtual | ~CameraOpenni () |
Static Public Member Functions | |
| static bool | available () |
Protected Member Functions | |
| virtual SensorData | captureImage (CameraInfo *info=0) |
Private Attributes | |
| boost::signals2::connection | connection_ |
| UMutex | dataMutex_ |
| USemaphore | dataReady_ |
| cv::Mat | depth_ |
| float | depthConstant_ |
| std::string | deviceId_ |
| pcl::Grabber * | interface_ |
| cv::Mat | rgb_ |
Definition at line 76 of file CameraRGBD.h.
| rtabmap::CameraOpenni::CameraOpenni | ( | const std::string & | deviceId = "", |
| float | imageRate = 0, |
||
| const Transform & | localTransform = Transform::getIdentity() |
||
| ) |
Definition at line 78 of file CameraRGBD.cpp.
| rtabmap::CameraOpenni::~CameraOpenni | ( | ) | [virtual] |
Definition at line 95 of file CameraRGBD.cpp.
| bool rtabmap::CameraOpenni::available | ( | ) | [static] |
Definition at line 86 of file CameraRGBD.cpp.
| SensorData rtabmap::CameraOpenni::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 206 of file CameraRGBD.cpp.
| std::string rtabmap::CameraOpenni::getSerial | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 195 of file CameraRGBD.cpp.
| bool rtabmap::CameraOpenni::init | ( | const std::string & | calibrationFolder = ".", |
| const std::string & | cameraName = "" |
||
| ) | [virtual] |
Implements rtabmap::Camera.
Definition at line 139 of file CameraRGBD.cpp.
| bool rtabmap::CameraOpenni::isCalibrated | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 186 of file CameraRGBD.cpp.
boost::signals2::connection rtabmap::CameraOpenni::connection_ [private] |
Definition at line 105 of file CameraRGBD.h.
UMutex rtabmap::CameraOpenni::dataMutex_ [private] |
Definition at line 109 of file CameraRGBD.h.
USemaphore rtabmap::CameraOpenni::dataReady_ [private] |
Definition at line 110 of file CameraRGBD.h.
cv::Mat rtabmap::CameraOpenni::depth_ [private] |
Definition at line 106 of file CameraRGBD.h.
float rtabmap::CameraOpenni::depthConstant_ [private] |
Definition at line 108 of file CameraRGBD.h.
std::string rtabmap::CameraOpenni::deviceId_ [private] |
Definition at line 104 of file CameraRGBD.h.
pcl::Grabber* rtabmap::CameraOpenni::interface_ [private] |
Definition at line 103 of file CameraRGBD.h.
cv::Mat rtabmap::CameraOpenni::rgb_ [private] |
Definition at line 107 of file CameraRGBD.h.