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

#include <CameraRGBD.h>

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

List of all members.

Public Member Functions

 CameraOpenNI2 (const std::string &deviceId="", float imageRate=0, const Transform &localTransform=Transform::getIdentity())
virtual std::string getSerial () const
virtual bool init (const std::string &calibrationFolder=".")
virtual bool isCalibrated () const
bool setAutoExposure (bool enabled)
bool setAutoWhiteBalance (bool enabled)
bool setExposure (int value)
bool setGain (int value)
bool setMirroring (bool enabled)
virtual ~CameraOpenNI2 ()

Static Public Member Functions

static bool available ()
static bool exposureGainAvailable ()

Protected Member Functions

virtual void captureImage (cv::Mat &rgb, cv::Mat &depth, float &fx, float &fy, float &cx, float &cy)

Private Attributes

openni::VideoStream * _color
openni::VideoStream * _depth
float _depthFx
float _depthFy
openni::Device * _device
std::string _deviceId

Detailed Description

Definition at line 200 of file CameraRGBD.h.


Constructor & Destructor Documentation

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

Definition at line 416 of file CameraRGBD.cpp.

Definition at line 436 of file CameraRGBD.cpp.


Member Function Documentation

Definition at line 398 of file CameraRGBD.cpp.

void rtabmap::CameraOpenNI2::captureImage ( cv::Mat &  rgb,
cv::Mat &  depth,
float &  fx,
float &  fy,
float &  cx,
float &  cy 
) [protected, virtual]

returned rgb and depth images should be already rectified

Implements rtabmap::CameraRGBD.

Definition at line 713 of file CameraRGBD.cpp.

Definition at line 407 of file CameraRGBD.cpp.

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

Implements rtabmap::CameraRGBD.

Definition at line 702 of file CameraRGBD.cpp.

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

Implements rtabmap::CameraRGBD.

Definition at line 524 of file CameraRGBD.cpp.

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

Implements rtabmap::CameraRGBD.

Definition at line 697 of file CameraRGBD.cpp.

Definition at line 465 of file CameraRGBD.cpp.

Definition at line 452 of file CameraRGBD.cpp.

Definition at line 478 of file CameraRGBD.cpp.

bool rtabmap::CameraOpenNI2::setGain ( int  value)

Definition at line 495 of file CameraRGBD.cpp.

bool rtabmap::CameraOpenNI2::setMirroring ( bool  enabled)

Definition at line 512 of file CameraRGBD.cpp.


Member Data Documentation

openni::VideoStream* rtabmap::CameraOpenNI2::_color [private]

Definition at line 229 of file CameraRGBD.h.

openni::VideoStream* rtabmap::CameraOpenNI2::_depth [private]

Definition at line 230 of file CameraRGBD.h.

Definition at line 231 of file CameraRGBD.h.

Definition at line 232 of file CameraRGBD.h.

openni::Device* rtabmap::CameraOpenNI2::_device [private]

Definition at line 228 of file CameraRGBD.h.

std::string rtabmap::CameraOpenNI2::_deviceId [private]

Definition at line 233 of file CameraRGBD.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:43