#include <CameraRealSense.h>
Public Types | |
enum | RGBSource { kColor, kInfrared, kFishEye } |
Public Member Functions | |
CameraRealSense (int deviceId=0, int presetRGB=0, int presetDepth=0, bool computeOdometry=false, float imageRate=0, const Transform &localTransform=CameraModel::opticalRotation()) | |
virtual std::string | getSerial () const |
virtual bool | init (const std::string &calibrationFolder=".", const std::string &cameraName="") |
virtual bool | isCalibrated () const |
virtual bool | odomProvided () const |
void | setDepthScaledToRGBSize (bool enabled) |
void | setRGBSource (RGBSource source) |
virtual | ~CameraRealSense () |
Public Member Functions inherited from rtabmap::Camera | |
float | getImageRate () const |
const Transform & | getLocalTransform () const |
bool | initFromFile (const std::string &calibrationPath) |
void | resetTimer () |
void | setImageRate (float imageRate) |
void | setLocalTransform (const Transform &localTransform) |
SensorData | takeImage (CameraInfo *info=0) |
virtual | ~Camera () |
Static Public Member Functions | |
static bool | available () |
Protected Member Functions | |
virtual SensorData | captureImage (CameraInfo *info=0) |
Protected Member Functions inherited from rtabmap::Camera | |
Camera (float imageRate=0, const Transform &localTransform=CameraModel::opticalRotation()) | |
int | getNextSeqID () |
Definition at line 52 of file CameraRealSense.h.
Enumerator | |
---|---|
kColor | |
kInfrared | |
kFishEye |
Definition at line 57 of file CameraRealSense.h.
rtabmap::CameraRealSense::CameraRealSense | ( | int | deviceId = 0 , |
int | presetRGB = 0 , |
||
int | presetDepth = 0 , |
||
bool | computeOdometry = false , |
||
float | imageRate = 0 , |
||
const Transform & | localTransform = CameraModel::opticalRotation() |
||
) |
Definition at line 56 of file CameraRealSense.cpp.
|
virtual |
Definition at line 80 of file CameraRealSense.cpp.
|
static |
Definition at line 47 of file CameraRealSense.cpp.
|
protectedvirtual |
returned rgb and depth images should be already rectified if calibration was loaded
Implements rtabmap::Camera.
Definition at line 859 of file CameraRealSense.cpp.
|
virtual |
Implements rtabmap::Camera.
Definition at line 825 of file CameraRealSense.cpp.
|
virtual |
Implements rtabmap::Camera.
Definition at line 257 of file CameraRealSense.cpp.
|
virtual |
Implements rtabmap::Camera.
Definition at line 820 of file CameraRealSense.cpp.
|
virtual |
Reimplemented from rtabmap::Camera.
Definition at line 840 of file CameraRealSense.cpp.
void rtabmap::CameraRealSense::setDepthScaledToRGBSize | ( | bool | enabled | ) |
Definition at line 145 of file CameraRealSense.cpp.
void rtabmap::CameraRealSense::setRGBSource | ( | RGBSource | source | ) |
Definition at line 150 of file CameraRealSense.cpp.