#include <Camera.h>
Public Member Functions | |
float | getImageRate () const |
const Transform & | getLocalTransform () const |
virtual std::string | getSerial () const =0 |
virtual bool | init (const std::string &calibrationFolder=".", const std::string &cameraName="")=0 |
virtual bool | isCalibrated () const =0 |
virtual bool | odomProvided () const |
void | setImageRate (float imageRate) |
void | setLocalTransform (const Transform &localTransform) |
SensorData | takeImage (CameraInfo *info=0) |
virtual | ~Camera () |
Protected Member Functions | |
Camera (float imageRate=0, const Transform &localTransform=Transform::getIdentity()) | |
virtual SensorData | captureImage (CameraInfo *info=0)=0 |
int | getNextSeqID () |
Private Attributes | |
UTimer * | _frameRateTimer |
float | _imageRate |
Transform | _localTransform |
int | _seq |
cv::Size | _targetImageSize |
rtabmap::Camera::~Camera | ( | ) | [virtual] |
Definition at line 55 of file Camera.cpp.
rtabmap::Camera::Camera | ( | float | imageRate = 0 , |
const Transform & | localTransform = Transform::getIdentity() |
||
) | [protected] |
Constructor
imageRate | : image/second , 0 for fast as the camera can |
Definition at line 46 of file Camera.cpp.
virtual SensorData rtabmap::Camera::captureImage | ( | CameraInfo * | info = 0 | ) | [protected, pure virtual] |
returned rgb and depth images should be already rectified if calibration was loaded
Implemented in rtabmap::CameraRGBDImages, rtabmap::CameraFreenect2, rtabmap::CameraStereoVideo, rtabmap::CameraFreenect, rtabmap::CameraVideo, rtabmap::CameraStereoImages, rtabmap::CameraOpenNI2, rtabmap::CameraStereoZed, rtabmap::CameraOpenNICV, rtabmap::CameraImages, rtabmap::CameraOpenni, rtabmap::CameraStereoFlyCapture2, rtabmap::CameraTango, rtabmap::CameraStereoDC1394, and rtabmap::DBReader.
float rtabmap::Camera::getImageRate | ( | ) | const [inline] |
const Transform& rtabmap::Camera::getLocalTransform | ( | ) | const [inline] |
int rtabmap::Camera::getNextSeqID | ( | ) | [inline, protected] |
virtual std::string rtabmap::Camera::getSerial | ( | ) | const [pure virtual] |
Implemented in rtabmap::CameraRGBDImages, rtabmap::CameraFreenect2, rtabmap::CameraStereoVideo, rtabmap::CameraFreenect, rtabmap::CameraVideo, rtabmap::CameraStereoImages, rtabmap::CameraOpenNI2, rtabmap::CameraStereoZed, rtabmap::CameraOpenNICV, rtabmap::CameraOpenni, rtabmap::CameraStereoFlyCapture2, rtabmap::CameraTango, rtabmap::CameraStereoDC1394, rtabmap::DBReader, and rtabmap::CameraImages.
virtual bool rtabmap::Camera::init | ( | const std::string & | calibrationFolder = "." , |
const std::string & | cameraName = "" |
||
) | [pure virtual] |
Implemented in rtabmap::CameraRGBDImages, rtabmap::CameraFreenect2, rtabmap::CameraStereoVideo, rtabmap::CameraFreenect, rtabmap::CameraVideo, rtabmap::CameraStereoImages, rtabmap::CameraOpenNI2, rtabmap::CameraStereoZed, rtabmap::CameraOpenNICV, rtabmap::CameraOpenni, rtabmap::CameraStereoFlyCapture2, rtabmap::CameraTango, rtabmap::CameraStereoDC1394, rtabmap::DBReader, and rtabmap::CameraImages.
virtual bool rtabmap::Camera::isCalibrated | ( | ) | const [pure virtual] |
Implemented in rtabmap::CameraRGBDImages, rtabmap::CameraFreenect2, rtabmap::CameraStereoVideo, rtabmap::CameraFreenect, rtabmap::CameraVideo, rtabmap::CameraStereoImages, rtabmap::CameraOpenNI2, rtabmap::CameraStereoZed, rtabmap::CameraOpenNICV, rtabmap::CameraOpenni, rtabmap::CameraStereoFlyCapture2, rtabmap::CameraTango, rtabmap::CameraStereoDC1394, rtabmap::DBReader, and rtabmap::CameraImages.
virtual bool rtabmap::Camera::odomProvided | ( | ) | const [inline, virtual] |
Reimplemented in rtabmap::CameraStereoZed, and rtabmap::DBReader.
void rtabmap::Camera::setImageRate | ( | float | imageRate | ) | [inline] |
void rtabmap::Camera::setLocalTransform | ( | const Transform & | localTransform | ) | [inline] |
SensorData rtabmap::Camera::takeImage | ( | CameraInfo * | info = 0 | ) |
Definition at line 62 of file Camera.cpp.
UTimer* rtabmap::Camera::_frameRateTimer [private] |
float rtabmap::Camera::_imageRate [private] |
Transform rtabmap::Camera::_localTransform [private] |
int rtabmap::Camera::_seq [private] |
cv::Size rtabmap::Camera::_targetImageSize [private] |