#include <SensorData.h>
Public Member Functions | |
void | addEnvSensor (const EnvSensor &sensor) |
void | addGlobalDescriptor (const GlobalDescriptor &descriptor) |
const std::vector< CameraModel > & | cameraModels () const |
void | clearCompressedData (bool images=true, bool scan=true, bool userData=true) |
void | clearGlobalDescriptors () |
void | clearOccupancyGridRaw () |
void | clearRawData (bool images=true, bool scan=true, bool userData=true) |
const cv::Mat & | depthOrRightCompressed () const |
const cv::Mat & | depthOrRightRaw () const |
cv::Mat | depthRaw () const |
const cv::Mat & | descriptors () const |
const EnvSensors & | envSensors () const |
unsigned long | getMemoryUsed () const |
const std::vector< GlobalDescriptor > & | globalDescriptors () const |
const Transform & | globalPose () const |
const cv::Mat & | globalPoseCovariance () const |
const GPS & | gps () 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 Transform & | groundTruth () const |
int | id () const |
const cv::Mat & | imageCompressed () const |
const cv::Mat & | imageRaw () const |
const IMU & | imu () 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 Landmarks & | landmarks () const |
const LaserScan & | laserScanCompressed () const |
const LaserScan & | laserScanRaw () const |
cv::Mat | rightRaw () const |
RTABMAP_DEPRECATED (void setImageRaw(const cv::Mat &image),"Use setRGBDImage() or setStereoImage() with clearNotUpdated=false or removeRawData() instead. To be backward compatible, this function doesn't clear compressed data.") | |
RTABMAP_DEPRECATED (void setDepthOrRightRaw(const cv::Mat &image),"Use setRGBDImage() or setStereoImage() with clearNotUpdated=false or removeRawData() instead. To be backward compatible, this function doesn't clear compressed data.") | |
RTABMAP_DEPRECATED (void setLaserScanRaw(const LaserScan &scan),"Use setLaserScan() with clearNotUpdated=false or removeRawData() instead. To be backward compatible, this function doesn't clear compressed data.") | |
RTABMAP_DEPRECATED (void setUserDataRaw(const cv::Mat &data),"Use setUserData() or removeRawData() instead.") | |
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 | setEnvSensors (const EnvSensors &sensors) |
void | setFeatures (const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors) |
void | setGlobalDescriptors (const std::vector< GlobalDescriptor > &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 | setIMU (const IMU &imu) |
void | setLandmarks (const Landmarks &landmarks) |
void | setLaserScan (const LaserScan &laserScan, bool clearPreviousData=true) |
void | setOccupancyGrid (const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty, float cellSize, const cv::Point3f &viewPoint) |
void | setRGBDImage (const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true) |
void | setRGBDImage (const cv::Mat &rgb, const cv::Mat &depth, const std::vector< CameraModel > &models, bool clearPreviousData=true) |
void | setStamp (double stamp) |
void | setStereoCameraModel (const StereoCameraModel &stereoCameraModel) |
void | setStereoImage (const cv::Mat &left, const cv::Mat &right, const StereoCameraModel &stereoCameraModel, bool clearPreviousData=true) |
void | setUserData (const cv::Mat &userData, bool clearPreviousData=true) |
double | stamp () const |
const StereoCameraModel & | stereoCameraModel () 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 |
EnvSensors | _envSensors |
std::vector< GlobalDescriptor > | _globalDescriptors |
cv::Mat | _groundCellsCompressed |
cv::Mat | _groundCellsRaw |
int | _id |
cv::Mat | _imageCompressed |
cv::Mat | _imageRaw |
std::vector< cv::KeyPoint > | _keypoints |
std::vector< cv::Point3f > | _keypoints3D |
Landmarks | _landmarks |
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_ |
An id is automatically generated if id=0.
Definition at line 51 of file SensorData.h.
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 62 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 77 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 93 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 111 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 127 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 145 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 161 of file SensorData.cpp.
rtabmap::SensorData::SensorData | ( | const IMU & | imu, |
int | id = 0 , |
||
double | stamp = 0.0 |
||
) |
Definition at line 178 of file SensorData.cpp.
|
virtual |
Definition at line 189 of file SensorData.cpp.
|
inline |
Definition at line 272 of file SensorData.h.
|
inline |
Definition at line 253 of file SensorData.h.
|
inline |
Definition at line 215 of file SensorData.h.
void rtabmap::SensorData::clearCompressedData | ( | bool | images = true , |
bool | scan = true , |
||
bool | userData = true |
||
) |
Clear compressed rgb/depth (left/right) images, compressed laser scan and compressed user data. Raw data are kept is set.
Definition at line 788 of file SensorData.cpp.
|
inline |
Definition at line 255 of file SensorData.h.
|
inline |
Definition at line 238 of file SensorData.h.
void rtabmap::SensorData::clearRawData | ( | bool | images = true , |
bool | scan = true , |
||
bool | userData = true |
||
) |
Clear raw rgb/depth (left/right) images, raw laser scan and raw user data. Compressed data are kept is set.
Definition at line 804 of file SensorData.cpp.
|
inline |
Definition at line 161 of file SensorData.h.
|
inline |
Definition at line 165 of file SensorData.h.
|
inline |
Definition at line 189 of file SensorData.h.
|
inline |
Definition at line 251 of file SensorData.h.
|
inline |
Definition at line 273 of file SensorData.h.
unsigned long rtabmap::SensorData::getMemoryUsed | ( | ) | const |
Definition at line 766 of file SensorData.cpp.
|
inline |
Definition at line 256 of file SensorData.h.
|
inline |
Definition at line 262 of file SensorData.h.
|
inline |
Definition at line 263 of file SensorData.h.
|
inline |
Definition at line 266 of file SensorData.h.
|
inline |
Definition at line 245 of file SensorData.h.
|
inline |
Definition at line 244 of file SensorData.h.
|
inline |
Definition at line 243 of file SensorData.h.
|
inline |
Definition at line 240 of file SensorData.h.
|
inline |
Definition at line 239 of file SensorData.h.
|
inline |
Definition at line 242 of file SensorData.h.
|
inline |
Definition at line 241 of file SensorData.h.
|
inline |
Definition at line 246 of file SensorData.h.
|
inline |
Definition at line 259 of file SensorData.h.
|
inline |
Definition at line 155 of file SensorData.h.
|
inline |
Definition at line 160 of file SensorData.h.
|
inline |
Definition at line 164 of file SensorData.h.
|
inline |
Definition at line 269 of file SensorData.h.
bool rtabmap::SensorData::isPointVisibleFromCameras | ( | const cv::Point3f & | pt | ) | const |
Definition at line 822 of file SensorData.cpp.
|
inline |
Definition at line 137 of file SensorData.h.
|
inline |
Definition at line 249 of file SensorData.h.
|
inline |
Definition at line 250 of file SensorData.h.
|
inline |
Definition at line 276 of file SensorData.h.
|
inline |
Definition at line 162 of file SensorData.h.
|
inline |
Definition at line 166 of file SensorData.h.
|
inline |
Definition at line 190 of file SensorData.h.
rtabmap::SensorData::RTABMAP_DEPRECATED | ( | void | setImageRawconst cv::Mat &image, |
"Use setRGBDImage() or setStereoImage() with | clearNotUpdated = false or removeRawData() instead. To be backward compatible , |
||
this function doesn't clear compressed data." | |||
) |
rtabmap::SensorData::RTABMAP_DEPRECATED | ( | void | setDepthOrRightRawconst cv::Mat &image, |
"Use setRGBDImage() or setStereoImage() with | clearNotUpdated = false or removeRawData() instead. To be backward compatible , |
||
this function doesn't clear compressed data." | |||
) |
rtabmap::SensorData::RTABMAP_DEPRECATED | ( | void | setLaserScanRawconst LaserScan &scan, |
"Use setLaserScan() with | clearNotUpdated = false or removeRawData() instead. To be backward compatible , |
||
this function doesn't clear compressed data." | |||
) |
rtabmap::SensorData::RTABMAP_DEPRECATED | ( | void | setUserDataRawconst cv::Mat &data, |
"Use setUserData() or removeRawData() instead." | |||
) |
|
inline |
Definition at line 184 of file SensorData.h.
|
inline |
Definition at line 185 of file SensorData.h.
|
inline |
Definition at line 271 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 757 of file SensorData.cpp.
|
inline |
Definition at line 254 of file SensorData.h.
|
inline |
Definition at line 261 of file SensorData.h.
|
inline |
Definition at line 265 of file SensorData.h.
|
inline |
Definition at line 258 of file SensorData.h.
|
inline |
Definition at line 156 of file SensorData.h.
|
inline |
Definition at line 268 of file SensorData.h.
|
inline |
Definition at line 275 of file SensorData.h.
void rtabmap::SensorData::setLaserScan | ( | const LaserScan & | laserScan, |
bool | clearPreviousData = true |
||
) |
Set laser scan data. Detect automatically if raw or compressed. A matrix of type CV_8UC1 with 1 row is considered as compressed.
clearPreviousData,clear | previous raw and compressed scans before setting the new one. |
Definition at line 337 of file SensorData.cpp.
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 400 of file SensorData.cpp.
void rtabmap::SensorData::setRGBDImage | ( | const cv::Mat & | rgb, |
const cv::Mat & | depth, | ||
const CameraModel & | model, | ||
bool | clearPreviousData = true |
||
) |
Set image data. Detect automatically if raw or compressed. A matrix of type CV_8UC1 with 1 row is considered as compressed.
clearPreviousData,clear | previous raw and compressed images before setting the new ones. |
Definition at line 193 of file SensorData.cpp.
void rtabmap::SensorData::setRGBDImage | ( | const cv::Mat & | rgb, |
const cv::Mat & | depth, | ||
const std::vector< CameraModel > & | models, | ||
bool | clearPreviousData = true |
||
) |
Definition at line 203 of file SensorData.cpp.
|
inline |
Definition at line 158 of file SensorData.h.
|
inline |
Definition at line 186 of file SensorData.h.
void rtabmap::SensorData::setStereoImage | ( | const cv::Mat & | left, |
const cv::Mat & | right, | ||
const StereoCameraModel & | stereoCameraModel, | ||
bool | clearPreviousData = true |
||
) |
Definition at line 270 of file SensorData.cpp.
void rtabmap::SensorData::setUserData | ( | const cv::Mat & | userData, |
bool | clearPreviousData = true |
||
) |
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.
clearPreviousData,clear | previous raw and compressed user data before setting the new one. |
Definition at line 378 of file SensorData.cpp.
|
inline |
Definition at line 157 of file SensorData.h.
|
inline |
Definition at line 216 of file SensorData.h.
void rtabmap::SensorData::uncompressData | ( | ) |
Definition at line 484 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 497 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 579 of file SensorData.cpp.
|
inline |
Definition at line 228 of file SensorData.h.
|
inline |
Definition at line 227 of file SensorData.h.
|
private |
Definition at line 304 of file SensorData.h.
|
private |
Definition at line 318 of file SensorData.h.
|
private |
Definition at line 297 of file SensorData.h.
|
private |
Definition at line 301 of file SensorData.h.
|
private |
Definition at line 330 of file SensorData.h.
|
private |
Definition at line 314 of file SensorData.h.
|
private |
Definition at line 317 of file SensorData.h.
|
private |
Definition at line 322 of file SensorData.h.
|
private |
Definition at line 333 of file SensorData.h.
|
private |
Definition at line 312 of file SensorData.h.
|
private |
Definition at line 315 of file SensorData.h.
|
private |
Definition at line 293 of file SensorData.h.
|
private |
Definition at line 296 of file SensorData.h.
|
private |
Definition at line 300 of file SensorData.h.
|
private |
Definition at line 328 of file SensorData.h.
|
private |
Definition at line 329 of file SensorData.h.
|
private |
Definition at line 325 of file SensorData.h.
|
private |
Definition at line 298 of file SensorData.h.
|
private |
Definition at line 302 of file SensorData.h.
|
private |
Definition at line 313 of file SensorData.h.
|
private |
Definition at line 316 of file SensorData.h.
|
private |
Definition at line 294 of file SensorData.h.
|
private |
Definition at line 305 of file SensorData.h.
|
private |
Definition at line 308 of file SensorData.h.
|
private |
Definition at line 309 of file SensorData.h.
|
private |
Definition at line 319 of file SensorData.h.
|
private |
Definition at line 337 of file SensorData.h.
|
private |
Definition at line 338 of file SensorData.h.
|
private |
Definition at line 340 of file SensorData.h.
|
private |
Definition at line 335 of file SensorData.h.
|
private |
Definition at line 342 of file SensorData.h.