#include <SensorCapture.h>
Class Camera
Definition at line 49 of file SensorCapture.h.
◆ ~SensorCapture()
rtabmap::SensorCapture::~SensorCapture |
( |
| ) |
|
|
virtual |
◆ SensorCapture()
Constructor
- Parameters
-
frameRate | the frame rate (Hz), 0 for fast as the sensor can |
localTransform | the transform from base frame to sensor frame |
Definition at line 46 of file SensorCapture.cpp.
◆ captureData()
◆ getFrameRate()
float rtabmap::SensorCapture::getFrameRate |
( |
| ) |
const |
|
inline |
◆ getLocalTransform()
const Transform& rtabmap::SensorCapture::getLocalTransform |
( |
| ) |
const |
|
inline |
◆ getNextSeqID()
int rtabmap::SensorCapture::getNextSeqID |
( |
| ) |
|
|
inlineprotected |
◆ getPose()
virtual bool rtabmap::SensorCapture::getPose |
( |
double |
stamp, |
|
|
Transform & |
pose, |
|
|
cv::Mat & |
covariance, |
|
|
double |
maxWaitTime = 0.06 |
|
) |
| |
|
inlinevirtual |
◆ getSerial()
virtual std::string rtabmap::SensorCapture::getSerial |
( |
| ) |
const |
|
pure virtual |
Implemented in rtabmap::LidarVLP16, rtabmap::CameraMobile, rtabmap::CameraOpenni, rtabmap::DBReader, rtabmap::CameraFreenect2, rtabmap::CameraStereoZed, rtabmap::CameraDepthAI, rtabmap::CameraK4W2, rtabmap::CameraRealSense, rtabmap::CameraARCore, rtabmap::CameraRealSense2, rtabmap::CameraStereoVideo, rtabmap::CameraStereoZedOC, rtabmap::CameraFreenect, rtabmap::CameraStereoImages, rtabmap::CameraK4A, rtabmap::CameraOpenNI2, rtabmap::CameraStereoTara, rtabmap::CameraMyntEye, rtabmap::CameraAREngine, rtabmap::CameraVideo, rtabmap::CameraTango, rtabmap::CameraStereoFlyCapture2, rtabmap::CameraImages, rtabmap::CameraOpenNICV, rtabmap::CameraStereoDC1394, and rtabmap::CameraSeerSense.
◆ init()
virtual bool rtabmap::SensorCapture::init |
( |
const std::string & |
calibrationFolder = "." , |
|
|
const std::string & |
cameraName = "" |
|
) |
| |
|
pure virtual |
Implemented in rtabmap::LidarVLP16, rtabmap::CameraMobile, rtabmap::CameraOpenni, rtabmap::DBReader, rtabmap::CameraFreenect2, rtabmap::CameraStereoZed, rtabmap::CameraDepthAI, rtabmap::CameraK4W2, rtabmap::CameraRealSense, rtabmap::CameraARCore, rtabmap::CameraRealSense2, rtabmap::CameraStereoVideo, rtabmap::CameraStereoZedOC, rtabmap::CameraFreenect, rtabmap::CameraStereoImages, rtabmap::CameraK4A, rtabmap::CameraOpenNI2, rtabmap::CameraStereoTara, rtabmap::CameraMyntEye, rtabmap::CameraAREngine, rtabmap::CameraVideo, rtabmap::CameraTango, rtabmap::CameraStereoFlyCapture2, rtabmap::CameraImages, rtabmap::CameraRGBDImages, rtabmap::CameraOpenNICV, rtabmap::CameraStereoDC1394, and rtabmap::CameraSeerSense.
◆ odomProvided()
virtual bool rtabmap::SensorCapture::odomProvided |
( |
| ) |
const |
|
inlinevirtual |
◆ resetTimer()
void rtabmap::SensorCapture::resetTimer |
( |
| ) |
|
◆ setFrameRate()
void rtabmap::SensorCapture::setFrameRate |
( |
float |
frameRate | ) |
|
|
inline |
◆ setLocalTransform()
void rtabmap::SensorCapture::setLocalTransform |
( |
const Transform & |
localTransform | ) |
|
|
inline |
◆ takeData()
◆ _frameRate
float rtabmap::SensorCapture::_frameRate |
|
private |
◆ _frameRateTimer
UTimer* rtabmap::SensorCapture::_frameRateTimer |
|
private |
◆ _localTransform
Transform rtabmap::SensorCapture::_localTransform |
|
private |
◆ _seq
int rtabmap::SensorCapture::_seq |
|
private |
The documentation for this class was generated from the following files: