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
void image_cb (const boost::shared_ptr< openni_wrapper::Image > &rgb, const boost::shared_ptr< openni_wrapper::DepthImage > &depth, float constant)
virtual bool init (const std::string &calibrationFolder=".")
virtual bool isCalibrated () const
virtual ~CameraOpenni ()

Static Public Member Functions

static bool available ()

Protected Member Functions

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

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 132 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 156 of file CameraRGBD.cpp.

Definition at line 164 of file CameraRGBD.cpp.


Member Function Documentation

static bool rtabmap::CameraOpenni::available ( ) [inline, static]

Definition at line 136 of file CameraRGBD.h.

void rtabmap::CameraOpenni::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 261 of file CameraRGBD.cpp.

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

Implements rtabmap::CameraRGBD.

Definition at line 252 of file CameraRGBD.cpp.

void rtabmap::CameraOpenni::image_cb ( const boost::shared_ptr< openni_wrapper::Image > &  rgb,
const boost::shared_ptr< openni_wrapper::DepthImage > &  depth,
float  constant 
)

Definition at line 181 of file CameraRGBD.cpp.

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

Implements rtabmap::CameraRGBD.

Definition at line 205 of file CameraRGBD.cpp.

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

Implements rtabmap::CameraRGBD.

Definition at line 247 of file CameraRGBD.cpp.


Member Data Documentation

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

Definition at line 160 of file CameraRGBD.h.

Definition at line 164 of file CameraRGBD.h.

Definition at line 165 of file CameraRGBD.h.

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

Definition at line 161 of file CameraRGBD.h.

Definition at line 163 of file CameraRGBD.h.

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

Definition at line 159 of file CameraRGBD.h.

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

Definition at line 158 of file CameraRGBD.h.

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

Definition at line 162 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