Public Member Functions | Static Public Member Functions | Protected Member Functions | List of all members
rtabmap::CameraDepthAI Class Reference

#include <CameraDepthAI.h>

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

Public Member Functions

 CameraDepthAI (const std::string &mxidOrName="", int resolution=1, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity())
 
virtual std::string getSerial () const
 
virtual bool init (const std::string &calibrationFolder=".", const std::string &cameraName="")
 
virtual bool isCalibrated () const
 
void setBlobPath (const std::string &blobPath)
 
void setCompanding (bool enabled, int width=96)
 
void setDepthProfile (int confThreshold=200, int lrcThreshold=5)
 
void setDetectFeatures (int detectFeatures=0)
 
void setExtendedDisparity (bool extendedDisparity)
 
void setGFTTDetector (bool useHarrisDetector=false, float minDistance=7.0f, int numTargetFeatures=1000)
 
void setIMU (bool imuPublished, bool publishInterIMU)
 
void setIrIntensity (float dotIntensity=0.0f, float floodIntensity=0.0f)
 
void setOutputMode (int outputMode=0)
 
void setRectification (bool useSpecTranslation, float alphaScaling=0.0f, bool enabled=true)
 
void setSubpixelMode (bool enabled, int fractionalBits=3)
 
void setSuperPointDetector (float threshold=0.01f, bool nms=true, int nmsRadius=4)
 
virtual ~CameraDepthAI ()
 
- Public Member Functions inherited from rtabmap::Camera
float getImageRate () const
 
bool initFromFile (const std::string &calibrationPath)
 
bool isInterIMUPublishing () const
 
void setImageRate (float imageRate)
 
void setInterIMUPublishing (bool enabled, IMUFilter *filter=0)
 
SensorData takeImage (SensorCaptureInfo *info=0)
 
virtual ~Camera ()
 
- Public Member Functions inherited from rtabmap::SensorCapture
float getFrameRate () const
 
const TransformgetLocalTransform () const
 
virtual bool getPose (double stamp, Transform &pose, cv::Mat &covariance, double maxWaitTime=0.06)
 
virtual bool odomProvided () const
 
void resetTimer ()
 
void setFrameRate (float frameRate)
 
void setLocalTransform (const Transform &localTransform)
 
SensorData takeData (SensorCaptureInfo *info=0)
 
virtual ~SensorCapture ()
 

Static Public Member Functions

static bool available ()
 

Protected Member Functions

virtual SensorData captureImage (SensorCaptureInfo *info=0)
 
- Protected Member Functions inherited from rtabmap::Camera
 Camera (float imageRate=0, const Transform &localTransform=Transform::getIdentity())
 
void postInterIMU (const IMU &imu, double stamp)
 
- Protected Member Functions inherited from rtabmap::SensorCapture
int getNextSeqID ()
 
 SensorCapture (float frameRate=0, const Transform &localTransform=Transform::getIdentity())
 

Detailed Description

Definition at line 44 of file CameraDepthAI.h.

Constructor & Destructor Documentation

◆ CameraDepthAI()

rtabmap::CameraDepthAI::CameraDepthAI ( const std::string mxidOrName = "",
int  resolution = 1,
float  imageRate = 0.0f,
const Transform localTransform = Transform::getIdentity() 
)

Definition at line 48 of file CameraDepthAI.cpp.

◆ ~CameraDepthAI()

rtabmap::CameraDepthAI::~CameraDepthAI ( )
virtual

Definition at line 84 of file CameraDepthAI.cpp.

Member Function Documentation

◆ available()

bool rtabmap::CameraDepthAI::available ( )
static

Definition at line 39 of file CameraDepthAI.cpp.

◆ captureImage()

SensorData rtabmap::CameraDepthAI::captureImage ( SensorCaptureInfo info = 0)
protectedvirtual

Implements rtabmap::Camera.

Definition at line 766 of file CameraDepthAI.cpp.

◆ getSerial()

std::string rtabmap::CameraDepthAI::getSerial ( ) const
virtual

Implements rtabmap::SensorCapture.

Definition at line 758 of file CameraDepthAI.cpp.

◆ init()

bool rtabmap::CameraDepthAI::init ( const std::string calibrationFolder = ".",
const std::string cameraName = "" 
)
virtual

Implements rtabmap::SensorCapture.

Definition at line 236 of file CameraDepthAI.cpp.

◆ isCalibrated()

bool rtabmap::CameraDepthAI::isCalibrated ( ) const
virtual

Implements rtabmap::Camera.

Definition at line 749 of file CameraDepthAI.cpp.

◆ setBlobPath()

void rtabmap::CameraDepthAI::setBlobPath ( const std::string blobPath)

Definition at line 205 of file CameraDepthAI.cpp.

◆ setCompanding()

void rtabmap::CameraDepthAI::setCompanding ( bool  enabled,
int  width = 96 
)

Definition at line 150 of file CameraDepthAI.cpp.

◆ setDepthProfile()

void rtabmap::CameraDepthAI::setDepthProfile ( int  confThreshold = 200,
int  lrcThreshold = 5 
)

Definition at line 103 of file CameraDepthAI.cpp.

◆ setDetectFeatures()

void rtabmap::CameraDepthAI::setDetectFeatures ( int  detectFeatures = 0)

Definition at line 196 of file CameraDepthAI.cpp.

◆ setExtendedDisparity()

void rtabmap::CameraDepthAI::setExtendedDisparity ( bool  extendedDisparity)

Definition at line 113 of file CameraDepthAI.cpp.

◆ setGFTTDetector()

void rtabmap::CameraDepthAI::setGFTTDetector ( bool  useHarrisDetector = false,
float  minDistance = 7.0f,
int  numTargetFeatures = 1000 
)

Definition at line 214 of file CameraDepthAI.cpp.

◆ setIMU()

void rtabmap::CameraDepthAI::setIMU ( bool  imuPublished,
bool  publishInterIMU 
)

Definition at line 176 of file CameraDepthAI.cpp.

◆ setIrIntensity()

void rtabmap::CameraDepthAI::setIrIntensity ( float  dotIntensity = 0.0f,
float  floodIntensity = 0.0f 
)

Definition at line 186 of file CameraDepthAI.cpp.

◆ setOutputMode()

void rtabmap::CameraDepthAI::setOutputMode ( int  outputMode = 0)

Definition at line 94 of file CameraDepthAI.cpp.

◆ setRectification()

void rtabmap::CameraDepthAI::setRectification ( bool  useSpecTranslation,
float  alphaScaling = 0.0f,
bool  enabled = true 
)

Definition at line 165 of file CameraDepthAI.cpp.

◆ setSubpixelMode()

void rtabmap::CameraDepthAI::setSubpixelMode ( bool  enabled,
int  fractionalBits = 3 
)

Definition at line 135 of file CameraDepthAI.cpp.

◆ setSuperPointDetector()

void rtabmap::CameraDepthAI::setSuperPointDetector ( float  threshold = 0.01f,
bool  nms = true,
int  nmsRadius = 4 
)

Definition at line 225 of file CameraDepthAI.cpp.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jul 1 2024 02:42:44