Public Member Functions | Static Public Member Functions | Protected Member Functions | Private Attributes
rtabmap::CameraOpenni Class Reference

#include <CameraRGBD.h>

Inheritance diagram for rtabmap::CameraOpenni:
Inheritance graph
[legend]

List of all members.

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_

Detailed Description

Definition at line 107 of file CameraRGBD.h.


Constructor & Destructor Documentation

rtabmap::CameraOpenni::CameraOpenni ( const std::string &  deviceId = "",
float  imageRate = 0,
const Transform localTransform = Transform::getIdentity() 
)

Definition at line 102 of file CameraRGBD.cpp.

Definition at line 119 of file CameraRGBD.cpp.


Member Function Documentation

Definition at line 110 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 230 of file CameraRGBD.cpp.

std::string rtabmap::CameraOpenni::getSerial ( ) const [virtual]

Implements rtabmap::Camera.

Definition at line 219 of file CameraRGBD.cpp.

bool rtabmap::CameraOpenni::init ( const std::string &  calibrationFolder = ".",
const std::string &  cameraName = "" 
) [virtual]

Implements rtabmap::Camera.

Definition at line 163 of file CameraRGBD.cpp.

bool rtabmap::CameraOpenni::isCalibrated ( ) const [virtual]

Implements rtabmap::Camera.

Definition at line 210 of file CameraRGBD.cpp.


Member Data Documentation

boost::signals2::connection rtabmap::CameraOpenni::connection_ [private]

Definition at line 136 of file CameraRGBD.h.

Definition at line 140 of file CameraRGBD.h.

Definition at line 141 of file CameraRGBD.h.

cv::Mat rtabmap::CameraOpenni::depth_ [private]

Definition at line 137 of file CameraRGBD.h.

Definition at line 139 of file CameraRGBD.h.

std::string rtabmap::CameraOpenni::deviceId_ [private]

Definition at line 135 of file CameraRGBD.h.

pcl::Grabber* rtabmap::CameraOpenni::interface_ [private]

Definition at line 134 of file CameraRGBD.h.

cv::Mat rtabmap::CameraOpenni::rgb_ [private]

Definition at line 138 of file CameraRGBD.h.


The documentation for this class was generated from the following files:


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:41