#include <CameraRGBD.h>
Public Types | |
enum | Type { kTypeRGBDepthSD, kTypeRGBDepthHD, kTypeIRDepth, kTypeRGBIR } |
Public Member Functions | |
CameraFreenect2 (int deviceId=0, Type type=kTypeRGBDepthSD, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity()) | |
virtual std::string | getSerial () const |
virtual bool | init (const std::string &calibrationFolder=".") |
virtual bool | isCalibrated () const |
virtual | ~CameraFreenect2 () |
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 | |
libfreenect2::Freenect2Device * | dev_ |
int | deviceId_ |
libfreenect2::Freenect2 * | freenect2_ |
libfreenect2::SyncMultiFrameListener * | listener_ |
libfreenect2::PacketPipeline * | pipeline_ |
libfreenect2::Registration * | reg_ |
StereoCameraModel | stereoModel_ |
Type | type_ |
Definition at line 272 of file CameraRGBD.h.
Definition at line 278 of file CameraRGBD.h.
rtabmap::CameraFreenect2::CameraFreenect2 | ( | int | deviceId = 0 , |
Type | type = kTypeRGBDepthSD , |
||
float | imageRate = 0.0f , |
||
const Transform & | localTransform = Transform::getIdentity() |
||
) |
Definition at line 1111 of file CameraRGBD.cpp.
rtabmap::CameraFreenect2::~CameraFreenect2 | ( | ) | [virtual] |
Definition at line 1162 of file CameraRGBD.cpp.
bool rtabmap::CameraFreenect2::available | ( | ) | [static] |
Definition at line 1102 of file CameraRGBD.cpp.
void rtabmap::CameraFreenect2::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 1303 of file CameraRGBD.cpp.
std::string rtabmap::CameraFreenect2::getSerial | ( | ) | const [virtual] |
Implements rtabmap::CameraRGBD.
Definition at line 1292 of file CameraRGBD.cpp.
bool rtabmap::CameraFreenect2::init | ( | const std::string & | calibrationFolder = "." | ) | [virtual] |
Implements rtabmap::CameraRGBD.
Definition at line 1194 of file CameraRGBD.cpp.
bool rtabmap::CameraFreenect2::isCalibrated | ( | ) | const [virtual] |
Implements rtabmap::CameraRGBD.
Definition at line 1287 of file CameraRGBD.cpp.
libfreenect2::Freenect2Device* rtabmap::CameraFreenect2::dev_ [private] |
Definition at line 305 of file CameraRGBD.h.
int rtabmap::CameraFreenect2::deviceId_ [private] |
Definition at line 301 of file CameraRGBD.h.
libfreenect2::Freenect2* rtabmap::CameraFreenect2::freenect2_ [private] |
Definition at line 304 of file CameraRGBD.h.
libfreenect2::SyncMultiFrameListener* rtabmap::CameraFreenect2::listener_ [private] |
Definition at line 307 of file CameraRGBD.h.
libfreenect2::PacketPipeline* rtabmap::CameraFreenect2::pipeline_ [private] |
Definition at line 306 of file CameraRGBD.h.
libfreenect2::Registration* rtabmap::CameraFreenect2::reg_ [private] |
Definition at line 308 of file CameraRGBD.h.
Definition at line 303 of file CameraRGBD.h.
Type rtabmap::CameraFreenect2::type_ [private] |
Definition at line 302 of file CameraRGBD.h.