Public Member Functions | Private Attributes
rtabmap::SensorData Class Reference

#include <SensorData.h>

List of all members.

Public Member Functions

float baseline () const
float cx () const
float cy () const
cv::Mat depth () const
const cv::Mat & depthOrRightImage () const
const cv::Mat & descriptors () const
float fx () const
float fy () const
float fyOrBaseline () const
int id () const
const cv::Mat & image () const
bool isMetric () const
bool isValid () const
const std::vector< cv::KeyPoint > & keypoints () const
const cv::Mat & laserScan () const
int laserScanMaxPts () const
const TransformlocalTransform () const
const Transformpose () const
float poseRotVariance () const
float poseTransVariance () const
cv::Mat rightImage () const
 RTABMAP_DEPRECATED (bool empty() const,"Use !isValid() instead.")
 SensorData ()
 SensorData (const cv::Mat &image, int id=0, double stamp=0.0, const std::vector< unsigned char > &userData=std::vector< unsigned char >())
 SensorData (const cv::Mat &image, const cv::Mat &depthOrRightImage, float fx, float fyOrBaseline, float cx, float cy, const Transform &localTransform, const Transform &pose, float poseRotVariance, float poseTransVariance, int id, double stamp, const std::vector< unsigned char > &userData=std::vector< unsigned char >())
 SensorData (const cv::Mat &laserScan, int laserScanMaxPts, const cv::Mat &image, const cv::Mat &depthOrRightImage, float fx, float fyOrBaseline, float cx, float cy, const Transform &localTransform, const Transform &pose, float poseRotVariance, float poseTransVariance, int id, double stamp, const std::vector< unsigned char > &userData=std::vector< unsigned char >())
void setFeatures (const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &descriptors)
void setId (int id)
void setPose (const Transform &pose, float rotVariance, float transVariance)
void setStamp (double stamp)
void setUserData (const std::vector< unsigned char > &data)
double stamp () const
const std::vector< unsigned
char > & 
userData () const
virtual ~SensorData ()

Private Attributes

float _cx
float _cy
cv::Mat _depthOrRightImage
cv::Mat _descriptors
float _fx
float _fyOrBaseline
int _id
cv::Mat _image
std::vector< cv::KeyPoint > _keypoints
cv::Mat _laserScan
int _laserScanMaxPts
Transform _localTransform
Transform _pose
float _poseRotVariance
float _poseTransVariance
double _stamp
std::vector< unsigned char > _userData

Detailed Description

An id is automatically generated if id=0.

Definition at line 42 of file SensorData.h.


Constructor & Destructor Documentation

An id is automatically generated if id=0.

Definition at line 39 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const cv::Mat &  image,
int  id = 0,
double  stamp = 0.0,
const std::vector< unsigned char > &  userData = std::vector<unsigned char>() 
)

Definition at line 53 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const cv::Mat &  image,
const cv::Mat &  depthOrRightImage,
float  fx,
float  fyOrBaseline,
float  cx,
float  cy,
const Transform localTransform,
const Transform pose,
float  poseRotVariance,
float  poseTransVariance,
int  id,
double  stamp,
const std::vector< unsigned char > &  userData = std::vector<unsigned char>() 
)

Definition at line 76 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const cv::Mat &  laserScan,
int  laserScanMaxPts,
const cv::Mat &  image,
const cv::Mat &  depthOrRightImage,
float  fx,
float  fyOrBaseline,
float  cx,
float  cy,
const Transform localTransform,
const Transform pose,
float  poseRotVariance,
float  poseTransVariance,
int  id,
double  stamp,
const std::vector< unsigned char > &  userData = std::vector<unsigned char>() 
)

Definition at line 116 of file SensorData.cpp.

virtual rtabmap::SensorData::~SensorData ( ) [inline, virtual]

Definition at line 80 of file SensorData.h.


Member Function Documentation

float rtabmap::SensorData::baseline ( ) const [inline]

Definition at line 104 of file SensorData.h.

float rtabmap::SensorData::cx ( ) const [inline]

Definition at line 102 of file SensorData.h.

float rtabmap::SensorData::cy ( ) const [inline]

Definition at line 103 of file SensorData.h.

cv::Mat rtabmap::SensorData::depth ( ) const [inline]

Definition at line 95 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::depthOrRightImage ( ) const [inline]

Definition at line 97 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::descriptors ( ) const [inline]

Definition at line 117 of file SensorData.h.

float rtabmap::SensorData::fx ( ) const [inline]

Definition at line 100 of file SensorData.h.

float rtabmap::SensorData::fy ( ) const [inline]

Definition at line 101 of file SensorData.h.

float rtabmap::SensorData::fyOrBaseline ( ) const [inline]

Definition at line 105 of file SensorData.h.

int rtabmap::SensorData::id ( ) const [inline]

Definition at line 88 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::image ( ) const [inline]

Definition at line 87 of file SensorData.h.

bool rtabmap::SensorData::isMetric ( ) const [inline]

Definition at line 93 of file SensorData.h.

bool rtabmap::SensorData::isValid ( ) const [inline]

Definition at line 82 of file SensorData.h.

const std::vector<cv::KeyPoint>& rtabmap::SensorData::keypoints ( ) const [inline]

Definition at line 116 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::laserScan ( ) const [inline]

Definition at line 98 of file SensorData.h.

int rtabmap::SensorData::laserScanMaxPts ( ) const [inline]

Definition at line 99 of file SensorData.h.

Definition at line 107 of file SensorData.h.

const Transform& rtabmap::SensorData::pose ( ) const [inline]

Definition at line 106 of file SensorData.h.

float rtabmap::SensorData::poseRotVariance ( ) const [inline]

Definition at line 108 of file SensorData.h.

float rtabmap::SensorData::poseTransVariance ( ) const [inline]

Definition at line 109 of file SensorData.h.

cv::Mat rtabmap::SensorData::rightImage ( ) const [inline]

Definition at line 96 of file SensorData.h.

rtabmap::SensorData::RTABMAP_DEPRECATED ( bool empty()  const,
"Use !isValid() instead."   
)
void rtabmap::SensorData::setFeatures ( const std::vector< cv::KeyPoint > &  keypoints,
const cv::Mat &  descriptors 
) [inline]

Definition at line 111 of file SensorData.h.

void rtabmap::SensorData::setId ( int  id) [inline]

Definition at line 89 of file SensorData.h.

void rtabmap::SensorData::setPose ( const Transform pose,
float  rotVariance,
float  transVariance 
) [inline]

Definition at line 94 of file SensorData.h.

void rtabmap::SensorData::setStamp ( double  stamp) [inline]

Definition at line 91 of file SensorData.h.

void rtabmap::SensorData::setUserData ( const std::vector< unsigned char > &  data) [inline]

Definition at line 119 of file SensorData.h.

double rtabmap::SensorData::stamp ( ) const [inline]

Definition at line 90 of file SensorData.h.

const std::vector<unsigned char>& rtabmap::SensorData::userData ( ) const [inline]

Definition at line 120 of file SensorData.h.


Member Data Documentation

float rtabmap::SensorData::_cx [private]

Definition at line 132 of file SensorData.h.

float rtabmap::SensorData::_cy [private]

Definition at line 133 of file SensorData.h.

Definition at line 128 of file SensorData.h.

Definition at line 142 of file SensorData.h.

float rtabmap::SensorData::_fx [private]

Definition at line 130 of file SensorData.h.

Definition at line 131 of file SensorData.h.

int rtabmap::SensorData::_id [private]

Definition at line 124 of file SensorData.h.

cv::Mat rtabmap::SensorData::_image [private]

Definition at line 123 of file SensorData.h.

std::vector<cv::KeyPoint> rtabmap::SensorData::_keypoints [private]

Definition at line 141 of file SensorData.h.

Definition at line 129 of file SensorData.h.

Definition at line 138 of file SensorData.h.

Definition at line 135 of file SensorData.h.

Definition at line 134 of file SensorData.h.

Definition at line 136 of file SensorData.h.

Definition at line 137 of file SensorData.h.

double rtabmap::SensorData::_stamp [private]

Definition at line 125 of file SensorData.h.

std::vector<unsigned char> rtabmap::SensorData::_userData [private]

Definition at line 145 of file SensorData.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:44