#include <CameraRGBD.h>
Public Types | |
enum | Type { kTypeColor2DepthSD, kTypeDepth2ColorSD, kTypeDepth2ColorHD, kTypeDepth2ColorHD2, kTypeIRDepth, kTypeColorIR } |
Public Member Functions | |
CameraFreenect2 (int deviceId=0, Type type=kTypeColor2DepthSD, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity(), float minDepth=0.3f, float maxDepth=12.0f, bool bilateralFiltering=true, bool edgeAwareFiltering=true, bool noiseFiltering=true) | |
virtual std::string | getSerial () const |
virtual bool | init (const std::string &calibrationFolder=".", const std::string &cameraName="") |
virtual bool | isCalibrated () const |
virtual | ~CameraFreenect2 () |
Static Public Member Functions | |
static bool | available () |
Protected Member Functions | |
virtual SensorData | captureImage (CameraInfo *info=0) |
Private Attributes | |
bool | bilateralFiltering_ |
libfreenect2::Freenect2Device * | dev_ |
int | deviceId_ |
bool | edgeAwareFiltering_ |
libfreenect2::Freenect2 * | freenect2_ |
libfreenect2::SyncMultiFrameListener * | listener_ |
float | maxKinect2Depth_ |
float | minKinect2Depth_ |
bool | noiseFiltering_ |
libfreenect2::Registration * | reg_ |
StereoCameraModel | stereoModel_ |
Type | type_ |
Definition at line 219 of file CameraRGBD.h.
kTypeColor2DepthSD | |
kTypeDepth2ColorSD | |
kTypeDepth2ColorHD | |
kTypeDepth2ColorHD2 | |
kTypeIRDepth | |
kTypeColorIR |
Definition at line 225 of file CameraRGBD.h.
rtabmap::CameraFreenect2::CameraFreenect2 | ( | int | deviceId = 0 , |
Type | type = kTypeColor2DepthSD , |
||
float | imageRate = 0.0f , |
||
const Transform & | localTransform = Transform::getIdentity() , |
||
float | minDepth = 0.3f , |
||
float | maxDepth = 12.0f , |
||
bool | bilateralFiltering = true , |
||
bool | edgeAwareFiltering = true , |
||
bool | noiseFiltering = true |
||
) |
Definition at line 1088 of file CameraRGBD.cpp.
rtabmap::CameraFreenect2::~CameraFreenect2 | ( | ) | [virtual] |
Definition at line 1132 of file CameraRGBD.cpp.
bool rtabmap::CameraFreenect2::available | ( | ) | [static] |
Definition at line 1079 of file CameraRGBD.cpp.
SensorData rtabmap::CameraFreenect2::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 1311 of file CameraRGBD.cpp.
std::string rtabmap::CameraFreenect2::getSerial | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 1300 of file CameraRGBD.cpp.
bool rtabmap::CameraFreenect2::init | ( | const std::string & | calibrationFolder = "." , |
const std::string & | cameraName = "" |
||
) | [virtual] |
Implements rtabmap::Camera.
Definition at line 1161 of file CameraRGBD.cpp.
bool rtabmap::CameraFreenect2::isCalibrated | ( | ) | const [virtual] |
Implements rtabmap::Camera.
Definition at line 1295 of file CameraRGBD.cpp.
bool rtabmap::CameraFreenect2::bilateralFiltering_ [private] |
Definition at line 264 of file CameraRGBD.h.
libfreenect2::Freenect2Device* rtabmap::CameraFreenect2::dev_ [private] |
Definition at line 259 of file CameraRGBD.h.
int rtabmap::CameraFreenect2::deviceId_ [private] |
Definition at line 255 of file CameraRGBD.h.
bool rtabmap::CameraFreenect2::edgeAwareFiltering_ [private] |
Definition at line 265 of file CameraRGBD.h.
libfreenect2::Freenect2* rtabmap::CameraFreenect2::freenect2_ [private] |
Definition at line 258 of file CameraRGBD.h.
libfreenect2::SyncMultiFrameListener* rtabmap::CameraFreenect2::listener_ [private] |
Definition at line 260 of file CameraRGBD.h.
float rtabmap::CameraFreenect2::maxKinect2Depth_ [private] |
Definition at line 263 of file CameraRGBD.h.
float rtabmap::CameraFreenect2::minKinect2Depth_ [private] |
Definition at line 262 of file CameraRGBD.h.
bool rtabmap::CameraFreenect2::noiseFiltering_ [private] |
Definition at line 266 of file CameraRGBD.h.
libfreenect2::Registration* rtabmap::CameraFreenect2::reg_ [private] |
Definition at line 261 of file CameraRGBD.h.
Definition at line 257 of file CameraRGBD.h.
Type rtabmap::CameraFreenect2::type_ [private] |
Definition at line 256 of file CameraRGBD.h.