Public Member Functions | Private Attributes | List of all members
rtabmap::SensorData Class Reference

#include <SensorData.h>

Public Member Functions

const std::vector< CameraModel > & cameraModels () const
 
void clearCompressedData ()
 
void clearOccupancyGridRaw ()
 
const cv::Mat & depthOrRightCompressed () const
 
const cv::Mat & depthOrRightRaw () const
 
cv::Mat depthRaw () const
 
const cv::Mat & descriptors () const
 
long getMemoryUsed () const
 
const TransformglobalPose () const
 
const cv::Mat & globalPoseCovariance () const
 
const GPSgps () const
 
float gridCellSize () const
 
const cv::Mat & gridEmptyCellsCompressed () const
 
const cv::Mat & gridEmptyCellsRaw () const
 
const cv::Mat & gridGroundCellsCompressed () const
 
const cv::Mat & gridGroundCellsRaw () const
 
const cv::Mat & gridObstacleCellsCompressed () const
 
const cv::Mat & gridObstacleCellsRaw () const
 
const cv::Point3f & gridViewPoint () const
 
const TransformgroundTruth () const
 
int id () const
 
const cv::Mat & imageCompressed () const
 
const cv::Mat & imageRaw () const
 
const IMUimu () const
 
bool isPointVisibleFromCameras (const cv::Point3f &pt) const
 
bool isValid () const
 
const std::vector< cv::KeyPoint > & keypoints () const
 
const std::vector< cv::Point3f > & keypoints3D () const
 
const LaserScanlaserScanCompressed () const
 
const LaserScanlaserScanRaw () const
 
cv::Mat rightRaw () const
 
 SensorData ()
 
 SensorData (const cv::Mat &image, int id=0, double stamp=0.0, const cv::Mat &userData=cv::Mat())
 
 SensorData (const cv::Mat &image, const CameraModel &cameraModel, int id=0, double stamp=0.0, const cv::Mat &userData=cv::Mat())
 
 SensorData (const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &cameraModel, int id=0, double stamp=0.0, const cv::Mat &userData=cv::Mat())
 
 SensorData (const LaserScan &laserScan, const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &cameraModel, int id=0, double stamp=0.0, const cv::Mat &userData=cv::Mat())
 
 SensorData (const cv::Mat &rgb, const cv::Mat &depth, const std::vector< CameraModel > &cameraModels, int id=0, double stamp=0.0, const cv::Mat &userData=cv::Mat())
 
 SensorData (const LaserScan &laserScan, const cv::Mat &rgb, const cv::Mat &depth, const std::vector< CameraModel > &cameraModels, int id=0, double stamp=0.0, const cv::Mat &userData=cv::Mat())
 
 SensorData (const cv::Mat &left, const cv::Mat &right, const StereoCameraModel &cameraModel, int id=0, double stamp=0.0, const cv::Mat &userData=cv::Mat())
 
 SensorData (const LaserScan &laserScan, const cv::Mat &left, const cv::Mat &right, const StereoCameraModel &cameraModel, int id=0, double stamp=0.0, const cv::Mat &userData=cv::Mat())
 
 SensorData (const IMU &imu, int id=0, double stamp=0.0)
 
void setCameraModel (const CameraModel &model)
 
void setCameraModels (const std::vector< CameraModel > &models)
 
void setDepthOrRightRaw (const cv::Mat &depthOrImageRaw)
 
void setFeatures (const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
 
void setGlobalPose (const Transform &pose, const cv::Mat &covariance)
 
void setGPS (const GPS &gps)
 
void setGroundTruth (const Transform &pose)
 
void setId (int id)
 
void setImageRaw (const cv::Mat &imageRaw)
 
void setIMU (const IMU &imu)
 
void setLaserScanRaw (const LaserScan &laserScanRaw)
 
void setOccupancyGrid (const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty, float cellSize, const cv::Point3f &viewPoint)
 
void setStamp (double stamp)
 
void setStereoCameraModel (const StereoCameraModel &stereoCameraModel)
 
void setUserData (const cv::Mat &userData)
 
void setUserDataRaw (const cv::Mat &userDataRaw)
 
double stamp () const
 
const StereoCameraModelstereoCameraModel () const
 
void uncompressData ()
 
void uncompressData (cv::Mat *imageRaw, cv::Mat *depthOrRightRaw, LaserScan *laserScanRaw=0, cv::Mat *userDataRaw=0, cv::Mat *groundCellsRaw=0, cv::Mat *obstacleCellsRaw=0, cv::Mat *emptyCellsRaw=0)
 
void uncompressDataConst (cv::Mat *imageRaw, cv::Mat *depthOrRightRaw, LaserScan *laserScanRaw=0, cv::Mat *userDataRaw=0, cv::Mat *groundCellsRaw=0, cv::Mat *obstacleCellsRaw=0, cv::Mat *emptyCellsRaw=0) const
 
const cv::Mat & userDataCompressed () const
 
const cv::Mat & userDataRaw () const
 
virtual ~SensorData ()
 

Private Attributes

std::vector< CameraModel_cameraModels
 
float _cellSize
 
cv::Mat _depthOrRightCompressed
 
cv::Mat _depthOrRightRaw
 
cv::Mat _descriptors
 
cv::Mat _emptyCellsCompressed
 
cv::Mat _emptyCellsRaw
 
cv::Mat _groundCellsCompressed
 
cv::Mat _groundCellsRaw
 
int _id
 
cv::Mat _imageCompressed
 
cv::Mat _imageRaw
 
std::vector< cv::KeyPoint > _keypoints
 
std::vector< cv::Point3f > _keypoints3D
 
LaserScan _laserScanCompressed
 
LaserScan _laserScanRaw
 
cv::Mat _obstacleCellsCompressed
 
cv::Mat _obstacleCellsRaw
 
double _stamp
 
StereoCameraModel _stereoCameraModel
 
cv::Mat _userDataCompressed
 
cv::Mat _userDataRaw
 
cv::Point3f _viewPoint
 
Transform globalPose_
 
cv::Mat globalPoseCovariance_
 
GPS gps_
 
Transform groundTruth_
 
IMU imu_
 

Detailed Description

An id is automatically generated if id=0.

Definition at line 48 of file SensorData.h.

Constructor & Destructor Documentation

rtabmap::SensorData::SensorData ( )

Definition at line 40 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const cv::Mat &  image,
int  id = 0,
double  stamp = 0.0,
const cv::Mat &  userData = cv::Mat() 
)

Definition at line 48 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const cv::Mat &  image,
const CameraModel cameraModel,
int  id = 0,
double  stamp = 0.0,
const cv::Mat &  userData = cv::Mat() 
)

Definition at line 80 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const cv::Mat &  rgb,
const cv::Mat &  depth,
const CameraModel cameraModel,
int  id = 0,
double  stamp = 0.0,
const cv::Mat &  userData = cv::Mat() 
)

Definition at line 114 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const LaserScan laserScan,
const cv::Mat &  rgb,
const cv::Mat &  depth,
const CameraModel cameraModel,
int  id = 0,
double  stamp = 0.0,
const cv::Mat &  userData = cv::Mat() 
)

Definition at line 161 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const cv::Mat &  rgb,
const cv::Mat &  depth,
const std::vector< CameraModel > &  cameraModels,
int  id = 0,
double  stamp = 0.0,
const cv::Mat &  userData = cv::Mat() 
)

Definition at line 217 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const LaserScan laserScan,
const cv::Mat &  rgb,
const cv::Mat &  depth,
const std::vector< CameraModel > &  cameraModels,
int  id = 0,
double  stamp = 0.0,
const cv::Mat &  userData = cv::Mat() 
)

Definition at line 263 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const cv::Mat &  left,
const cv::Mat &  right,
const StereoCameraModel cameraModel,
int  id = 0,
double  stamp = 0.0,
const cv::Mat &  userData = cv::Mat() 
)

Definition at line 319 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const LaserScan laserScan,
const cv::Mat &  left,
const cv::Mat &  right,
const StereoCameraModel cameraModel,
int  id = 0,
double  stamp = 0.0,
const cv::Mat &  userData = cv::Mat() 
)

Definition at line 367 of file SensorData.cpp.

rtabmap::SensorData::SensorData ( const IMU imu,
int  id = 0,
double  stamp = 0.0 
)

Definition at line 421 of file SensorData.cpp.

rtabmap::SensorData::~SensorData ( )
virtual

Definition at line 432 of file SensorData.cpp.

Member Function Documentation

const std::vector<CameraModel>& rtabmap::SensorData::cameraModels ( ) const
inline

Definition at line 193 of file SensorData.h.

void rtabmap::SensorData::clearCompressedData ( )
inline

Definition at line 251 of file SensorData.h.

void rtabmap::SensorData::clearOccupancyGridRaw ( )
inline

Definition at line 216 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::depthOrRightCompressed ( ) const
inline

Definition at line 158 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::depthOrRightRaw ( ) const
inline

Definition at line 162 of file SensorData.h.

cv::Mat rtabmap::SensorData::depthRaw ( ) const
inline

Definition at line 172 of file SensorData.h.

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

Definition at line 229 of file SensorData.h.

long rtabmap::SensorData::getMemoryUsed ( ) const

Definition at line 837 of file SensorData.cpp.

const Transform& rtabmap::SensorData::globalPose ( ) const
inline

Definition at line 235 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::globalPoseCovariance ( ) const
inline

Definition at line 236 of file SensorData.h.

const GPS& rtabmap::SensorData::gps ( ) const
inline

Definition at line 242 of file SensorData.h.

float rtabmap::SensorData::gridCellSize ( ) const
inline

Definition at line 223 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::gridEmptyCellsCompressed ( ) const
inline

Definition at line 222 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::gridEmptyCellsRaw ( ) const
inline

Definition at line 221 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::gridGroundCellsCompressed ( ) const
inline

Definition at line 218 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::gridGroundCellsRaw ( ) const
inline

Definition at line 217 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::gridObstacleCellsCompressed ( ) const
inline

Definition at line 220 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::gridObstacleCellsRaw ( ) const
inline

Definition at line 219 of file SensorData.h.

const cv::Point3f& rtabmap::SensorData::gridViewPoint ( ) const
inline

Definition at line 224 of file SensorData.h.

const Transform& rtabmap::SensorData::groundTruth ( ) const
inline

Definition at line 232 of file SensorData.h.

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

Definition at line 152 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::imageCompressed ( ) const
inline

Definition at line 157 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::imageRaw ( ) const
inline

Definition at line 161 of file SensorData.h.

const IMU& rtabmap::SensorData::imu ( ) const
inline

Definition at line 248 of file SensorData.h.

bool rtabmap::SensorData::isPointVisibleFromCameras ( const cv::Point3f &  pt) const

Definition at line 858 of file SensorData.cpp.

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

Definition at line 134 of file SensorData.h.

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

Definition at line 227 of file SensorData.h.

const std::vector<cv::Point3f>& rtabmap::SensorData::keypoints3D ( ) const
inline

Definition at line 228 of file SensorData.h.

const LaserScan& rtabmap::SensorData::laserScanCompressed ( ) const
inline

Definition at line 159 of file SensorData.h.

const LaserScan& rtabmap::SensorData::laserScanRaw ( ) const
inline

Definition at line 163 of file SensorData.h.

cv::Mat rtabmap::SensorData::rightRaw ( ) const
inline

Definition at line 173 of file SensorData.h.

void rtabmap::SensorData::setCameraModel ( const CameraModel model)
inline

Definition at line 167 of file SensorData.h.

void rtabmap::SensorData::setCameraModels ( const std::vector< CameraModel > &  models)
inline

Definition at line 168 of file SensorData.h.

void rtabmap::SensorData::setDepthOrRightRaw ( const cv::Mat &  depthOrImageRaw)
inline

Definition at line 165 of file SensorData.h.

void rtabmap::SensorData::setFeatures ( const std::vector< cv::KeyPoint > &  keypoints,
const std::vector< cv::Point3f > &  keypoints3D,
const cv::Mat &  descriptors 
)

Definition at line 828 of file SensorData.cpp.

void rtabmap::SensorData::setGlobalPose ( const Transform pose,
const cv::Mat &  covariance 
)
inline

Definition at line 234 of file SensorData.h.

void rtabmap::SensorData::setGPS ( const GPS gps)
inline

Definition at line 238 of file SensorData.h.

void rtabmap::SensorData::setGroundTruth ( const Transform pose)
inline

Definition at line 231 of file SensorData.h.

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

Definition at line 153 of file SensorData.h.

void rtabmap::SensorData::setImageRaw ( const cv::Mat &  imageRaw)
inline

Definition at line 164 of file SensorData.h.

void rtabmap::SensorData::setIMU ( const IMU imu)
inline

Definition at line 244 of file SensorData.h.

void rtabmap::SensorData::setLaserScanRaw ( const LaserScan laserScanRaw)
inline

Definition at line 166 of file SensorData.h.

void rtabmap::SensorData::setOccupancyGrid ( const cv::Mat &  ground,
const cv::Mat &  obstacles,
const cv::Mat &  empty,
float  cellSize,
const cv::Point3f &  viewPoint 
)

Definition at line 482 of file SensorData.cpp.

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

Definition at line 155 of file SensorData.h.

void rtabmap::SensorData::setStereoCameraModel ( const StereoCameraModel stereoCameraModel)
inline

Definition at line 169 of file SensorData.h.

void rtabmap::SensorData::setUserData ( const cv::Mat &  userData)

Set user data. Detect automatically if raw or compressed. If raw, the data is compressed too. A matrix of type CV_8UC1 with 1 row is considered as compressed. If you have one dimension unsigned 8 bits raw data, make sure to transpose it (to have multiple rows instead of multiple columns) in order to be detected as not compressed.

Definition at line 452 of file SensorData.cpp.

void rtabmap::SensorData::setUserDataRaw ( const cv::Mat &  userDataRaw)

Definition at line 436 of file SensorData.cpp.

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

Definition at line 154 of file SensorData.h.

const StereoCameraModel& rtabmap::SensorData::stereoCameraModel ( ) const
inline

Definition at line 194 of file SensorData.h.

void rtabmap::SensorData::uncompressData ( )

Definition at line 568 of file SensorData.cpp.

void rtabmap::SensorData::uncompressData ( cv::Mat *  imageRaw,
cv::Mat *  depthOrRightRaw,
LaserScan laserScanRaw = 0,
cv::Mat *  userDataRaw = 0,
cv::Mat *  groundCellsRaw = 0,
cv::Mat *  obstacleCellsRaw = 0,
cv::Mat *  emptyCellsRaw = 0 
)

Definition at line 581 of file SensorData.cpp.

void rtabmap::SensorData::uncompressDataConst ( cv::Mat *  imageRaw,
cv::Mat *  depthOrRightRaw,
LaserScan laserScanRaw = 0,
cv::Mat *  userDataRaw = 0,
cv::Mat *  groundCellsRaw = 0,
cv::Mat *  obstacleCellsRaw = 0,
cv::Mat *  emptyCellsRaw = 0 
) const

Definition at line 656 of file SensorData.cpp.

const cv::Mat& rtabmap::SensorData::userDataCompressed ( ) const
inline

Definition at line 206 of file SensorData.h.

const cv::Mat& rtabmap::SensorData::userDataRaw ( ) const
inline

Definition at line 205 of file SensorData.h.

Member Data Documentation

std::vector<CameraModel> rtabmap::SensorData::_cameraModels
private

Definition at line 267 of file SensorData.h.

float rtabmap::SensorData::_cellSize
private

Definition at line 281 of file SensorData.h.

cv::Mat rtabmap::SensorData::_depthOrRightCompressed
private

Definition at line 260 of file SensorData.h.

cv::Mat rtabmap::SensorData::_depthOrRightRaw
private

Definition at line 264 of file SensorData.h.

cv::Mat rtabmap::SensorData::_descriptors
private

Definition at line 287 of file SensorData.h.

cv::Mat rtabmap::SensorData::_emptyCellsCompressed
private

Definition at line 277 of file SensorData.h.

cv::Mat rtabmap::SensorData::_emptyCellsRaw
private

Definition at line 280 of file SensorData.h.

cv::Mat rtabmap::SensorData::_groundCellsCompressed
private

Definition at line 275 of file SensorData.h.

cv::Mat rtabmap::SensorData::_groundCellsRaw
private

Definition at line 278 of file SensorData.h.

int rtabmap::SensorData::_id
private

Definition at line 256 of file SensorData.h.

cv::Mat rtabmap::SensorData::_imageCompressed
private

Definition at line 259 of file SensorData.h.

cv::Mat rtabmap::SensorData::_imageRaw
private

Definition at line 263 of file SensorData.h.

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

Definition at line 285 of file SensorData.h.

std::vector<cv::Point3f> rtabmap::SensorData::_keypoints3D
private

Definition at line 286 of file SensorData.h.

LaserScan rtabmap::SensorData::_laserScanCompressed
private

Definition at line 261 of file SensorData.h.

LaserScan rtabmap::SensorData::_laserScanRaw
private

Definition at line 265 of file SensorData.h.

cv::Mat rtabmap::SensorData::_obstacleCellsCompressed
private

Definition at line 276 of file SensorData.h.

cv::Mat rtabmap::SensorData::_obstacleCellsRaw
private

Definition at line 279 of file SensorData.h.

double rtabmap::SensorData::_stamp
private

Definition at line 257 of file SensorData.h.

StereoCameraModel rtabmap::SensorData::_stereoCameraModel
private

Definition at line 268 of file SensorData.h.

cv::Mat rtabmap::SensorData::_userDataCompressed
private

Definition at line 271 of file SensorData.h.

cv::Mat rtabmap::SensorData::_userDataRaw
private

Definition at line 272 of file SensorData.h.

cv::Point3f rtabmap::SensorData::_viewPoint
private

Definition at line 282 of file SensorData.h.

Transform rtabmap::SensorData::globalPose_
private

Definition at line 291 of file SensorData.h.

cv::Mat rtabmap::SensorData::globalPoseCovariance_
private

Definition at line 292 of file SensorData.h.

GPS rtabmap::SensorData::gps_
private

Definition at line 294 of file SensorData.h.

Transform rtabmap::SensorData::groundTruth_
private

Definition at line 289 of file SensorData.h.

IMU rtabmap::SensorData::imu_
private

Definition at line 296 of file SensorData.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:43