Namespaces | Classes | Typedefs | Functions | Variables
rtabmap Namespace Reference

Namespaces

 graph
 
 util2d
 
 util3d
 

Classes

struct  AABB
 
class  AboutDialog
 
class  BayesFilter
 
class  BRISK
 
class  CalibrationDialog
 
class  Camera
 
class  CameraEvent
 
class  CameraFreenect
 
class  CameraFreenect2
 
class  CameraImages
 
class  CameraInfo
 
class  CameraK4W2
 
class  CameraModel
 
class  CameraOpenni
 
class  CameraOpenNI2
 
class  CameraOpenNICV
 
class  CameraRealSense
 
class  CameraRealSense2
 
class  CameraRGBDImages
 
class  CameraStereoDC1394
 
class  CameraStereoFlyCapture2
 
class  CameraStereoImages
 
class  CameraStereoVideo
 
class  CameraStereoZed
 
class  CameraTango
 
class  CameraTangoEvent
 
class  CameraThread
 
class  CameraVideo
 
class  CameraViewer
 
class  CloudViewer
 
class  CloudViewerCellPicker
 
class  CloudViewerInteractorStyle
 
class  CompressionThread
 
class  ConsoleWidget
 
class  CreateSimpleCalibrationDialog
 
class  CV_ORB
 
class  DatabaseViewer
 
class  DataRecorder
 
class  DBDriver
 
class  DBDriverSqlite3
 
class  DBReader
 
class  DepthCalibrationDialog
 
class  EditDepthArea
 
class  EpipolarGeometry
 
class  ExportBundlerDialog
 
class  ExportCloudsDialog
 
class  ExportDialog
 
class  FAST
 
class  FAST_BRIEF
 
class  FAST_FREAK
 
class  Feature2D
 
class  FlannIndex
 
class  GainCompensator
 
class  GeodeticCoords
 
class  GFTT
 
class  GFTT_BRIEF
 
class  GFTT_FREAK
 
class  GFTT_ORB
 
class  GPS
 
class  GraphViewer
 
class  ImageView
 
class  IMU
 
class  IMUEvent
 
class  IMUThread
 
class  KAZE
 
class  KeypointItem
 
class  LaserScan
 
class  LineItem
 
class  Link
 
class  LinkItem
 
class  LoopClosureViewer
 
class  MainWindow
 
class  MapVisibilityWidget
 
class  Memory
 
class  NodeGPSItem
 
class  NodeItem
 
class  OccupancyGrid
 
class  OctoMap
 
class  Odometry
 
class  OdometryDVO
 
class  OdometryEvent
 
class  OdometryF2F
 
class  OdometryF2M
 
class  OdometryFovis
 
class  OdometryInfo
 
class  OdometryLOAM
 
class  OdometryMono
 
class  OdometryMSCKF
 
class  OdometryOkvis
 
class  OdometryORBSLAM2
 
class  OdometryResetEvent
 
class  OdometryThread
 
class  OdometryViewer
 
class  OdometryViso2
 
class  Optimizer
 
class  OptimizerCVSBA
 
class  OptimizerG2O
 
class  OptimizerGTSAM
 
class  OptimizerTORO
 
class  ORB
 
class  Parameters
 
class  ParametersToolBox
 
class  ParamEvent
 
class  ParticleFilter
 
class  PdfPlotCurve
 
class  PdfPlotItem
 
class  PoseEvent
 
class  PostProcessingDialog
 
class  PreferencesDialog
 
class  PreUpdateThread
 
class  ProgressDialog
 
class  ProgressEvent
 
class  ProgressionStatus
 
class  ProgressState
 
class  RecoveryState
 
class  Registration
 
class  RegistrationIcp
 
class  RegistrationInfo
 
class  RegistrationVis
 
class  Rtabmap
 
class  RtabmapColorOcTree
 
class  RtabmapColorOcTreeNode
 
class  RtabmapEvent
 
class  RtabmapEvent3DMap
 
class  RtabmapEventCmd
 
class  RtabmapEventInit
 
class  RtabmapGlobalPathEvent
 
class  RtabmapGoalStatusEvent
 
class  RtabmapLabelErrorEvent
 
class  RtabmapThread
 
class  SensorData
 
class  SIFT
 
class  Signature
 
class  Statistics
 
class  StatItem
 
class  StatsToolBox
 
class  Stereo
 
class  StereoBM
 
class  StereoCameraModel
 
class  StereoDense
 
class  StereoOpticalFlow
 
class  SURF
 
class  TexturingState
 
class  Transform
 
class  UserDataEvent
 
class  VisualWord
 
class  vtkImageMatSource
 
class  VWDictionary
 
class  WeightAgeIdKey
 

Typedefs

typedef std::map< std::string, std::string > ParametersMap
 
typedef std::pair< std::string, std::string > ParametersPair
 

Functions

float addNeighborProb (cv::Mat &prediction, unsigned int col, const std::map< int, int > &neighbors, const std::vector< double > &predictionLC, const std::map< int, int > &idToIndex)
 
void applyFovModel (double xu, double yu, double w, double w_inverse, double two_tan_w_div_two, double *xd, double *yd)
 
template<typename PointT >
void applyImpl (int index, typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const cv::Mat_< double > &gains, bool rgb)
 
chisel::PinholeCamera cameraModelToChiselCamera (const CameraModel &camera)
 
pcl::PolygonMesh::Ptr chiselToPolygonMesh (const chisel::MeshMap &meshMap, unsigned char r=100, unsigned char g=100, unsigned char b=100)
 
std::shared_ptr< chisel::ColorImage< unsigned char > > colorImageToChisel (const cv::Mat &image)
 
std::vector< unsigned char > RTABMAP_EXP compressData (const cv::Mat &data)
 
cv::Mat RTABMAP_EXP compressData2 (const cv::Mat &data)
 
std::vector< unsigned char > RTABMAP_EXP compressImage (const cv::Mat &image, const std::string &format=".png")
 
cv::Mat RTABMAP_EXP compressImage2 (const cv::Mat &image, const std::string &format=".png")
 
cv::Mat RTABMAP_EXP compressString (const std::string &str)
 
static void computeDescriptors (const Mat &image, std::vector< KeyPoint > &keypoints, Mat &descriptors, const std::vector< Point > &pattern, int dsize, int WTA_K)
 
static void computeKeyPoints (const std::vector< Mat > &imagePyramid, const std::vector< Mat > &maskPyramid, std::vector< std::vector< KeyPoint > > &allKeypoints, int nfeatures, int firstLevel, double scaleFactor, int edgeThreshold, int patchSize, int scoreType, ParametersMap fastParameters)
 
static void computeOrbDescriptor (const KeyPoint &kpt, const Mat &img, const Point *pattern, uchar *desc, int dsize, int WTA_K)
 
static void computeOrientation (const Mat &image, std::vector< KeyPoint > &keypoints, int halfPatchSize, const std::vector< int > &umax)
 
QIcon createIcon (const QColor &color)
 
std::vector< double > cumSum (const std::vector< double > &v)
 
bool RTABMAP_EXP databaseRecovery (const std::string &corruptedDatabase, bool keepCorruptedDatabase=true, std::string *errorMsg=0, ProgressState *progressState=0)
 
double DEG2RAD (const double x)
 
std::shared_ptr< chisel::DepthImage< float > > depthImageToChisel (const cv::Mat &image)
 
template<typename PointT >
void feedImpl (const std::map< int, typename pcl::PointCloud< PointT >::Ptr > &clouds, const std::map< int, pcl::IndicesPtr > &indices, const std::multimap< int, Link > &links, float maxCorrespondenceDistance, double minOverlap, double alpha, double beta, cv::Mat_< double > &gains, std::map< int, int > &idToIndex)
 
void floodfill (QImage &image, const cv::Mat &depthImage, int x, int y, float lastDepthValue, float error)
 
static float getScale (int level, int firstLevel, double scaleFactor)
 
static void HarrisResponses (const Mat &img, std::vector< KeyPoint > &pts, int blockSize, float harris_k)
 
static float IC_Angle (const Mat &image, const int half_k, Point2f pt, const std::vector< int > &u_max)
 
int inFrontOfBothCameras (const cv::Mat &x, const cv::Mat &xp, const cv::Mat &R, const cv::Mat &T)
 
void initFisheyeRectificationMap (const CameraModel &fisheyeModel, cv::Mat &mapX, cv::Mat &mapY)
 
static void initializeOrbPattern (const Point *pattern0, std::vector< Point > &pattern, int ntuples, int tupleSize, int poolSize)
 
static void makeRandomPattern (int patchSize, Point *pattern, int npoints)
 
void onFrameAvailableRouter (void *context, TangoCameraId id, const TangoImageBuffer *color)
 
void onPointCloudAvailableRouter (void *context, const TangoPointCloud *point_cloud)
 
void onPoseAvailableRouter (void *context, const TangoPoseData *pose)
 
void onTangoEventAvailableRouter (void *context, const TangoEvent *event)
 
RTABMAP_EXP std::ostream & operator<< (std::ostream &os, const Transform &s)
 
template<typename PointRGBT >
chisel::PointCloudPtr pointCloudRGBToChisel (const typename pcl::PointCloud< PointRGBT > &cloud, const Transform &transform=Transform::getIdentity())
 
template<typename PointT >
chisel::PointCloudPtr pointCloudToChisel (const typename pcl::PointCloud< PointT > &cloud, const Transform &transform=Transform::getIdentity())
 
double RAD2DEG (const double x)
 
std::vector< double > resample (const std::vector< double > &p, const std::vector< double > &w, bool normalizeWeights=false)
 
Eigen::Vector3f rotatePointAroundAxe (const Eigen::Vector3f &point, const Eigen::Vector3f &axis, float angle)
 
 RTABMAP_DEPRECATED (typedef SensorData Image,"rtabmap::Image class is renamed to rtabmap::SensorData, use the last one instead.")
 
bool sortCallback (const std::string &a, const std::string &b)
 
double sqr (uchar v)
 
double square (const double &value)
 
bool testAABBAABB (const AABB &a, const AABB &b)
 
cv::Mat RTABMAP_EXP uncompressData (const cv::Mat &bytes)
 
cv::Mat RTABMAP_EXP uncompressData (const std::vector< unsigned char > &bytes)
 
cv::Mat RTABMAP_EXP uncompressData (const unsigned char *bytes, unsigned long size)
 
cv::Mat RTABMAP_EXP uncompressImage (const cv::Mat &bytes)
 
cv::Mat RTABMAP_EXP uncompressImage (const std::vector< unsigned char > &bytes)
 
std::string RTABMAP_EXP uncompressString (const cv::Mat &bytes)
 
 vtkStandardNewMacro (CloudViewerInteractorStyle)
 
 vtkStandardNewMacro (CloudViewerCellPicker)
 
 vtkStandardNewMacro (vtkImageMatSource)
 

Variables

static int bit_pattern_31_ [256 *4]
 
static const int frustum_indices []
 
static const float frustum_vertices []
 
const float HARRIS_K = 0.04f
 
const int holeSize = 5
 
const int kVersionStringLength = 128
 
const float maxDepthError = 0.10
 
static rtabmap::Transform opticalRotation (1.0f, 0.0f, 0.0f, 0.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f,-1.0f, 0.0f)
 
const int scanDownsampling = 1
 

Detailed Description

File from OpenCV (see License below), modified by Mathieu Labbe 2016

Typedef Documentation

typedef std::map<std::string, std::string> rtabmap::ParametersMap

Definition at line 41 of file Parameters.h.

typedef std::pair<std::string, std::string> rtabmap::ParametersPair

Definition at line 42 of file Parameters.h.

Function Documentation

float rtabmap::addNeighborProb ( cv::Mat &  prediction,
unsigned int  col,
const std::map< int, int > &  neighbors,
const std::vector< double > &  predictionLC,
const std::map< int, int > &  idToIndex 
)

Definition at line 228 of file BayesFilter.cpp.

void rtabmap::applyFovModel ( double  xu,
double  yu,
double  w,
double  w_inverse,
double  two_tan_w_div_two,
double *  xd,
double *  yd 
)

Definition at line 138 of file CameraTango.cpp.

template<typename PointT >
void rtabmap::applyImpl ( int  index,
typename pcl::PointCloud< PointT >::Ptr &  cloud,
const pcl::IndicesPtr &  indices,
const cv::Mat_< double > &  gains,
bool  rgb 
)

Definition at line 393 of file GainCompensator.cpp.

chisel::PinholeCamera rtabmap::cameraModelToChiselCamera ( const CameraModel camera)

Definition at line 35 of file chisel_conversions.h.

pcl::PolygonMesh::Ptr rtabmap::chiselToPolygonMesh ( const chisel::MeshMap &  meshMap,
unsigned char  r = 100,
unsigned char  g = 100,
unsigned char  b = 100 
)

Definition at line 109 of file chisel_conversions.h.

std::shared_ptr<chisel::ColorImage<unsigned char> > rtabmap::colorImageToChisel ( const cv::Mat &  image)

Definition at line 19 of file chisel_conversions.h.

std::vector< unsigned char > rtabmap::compressData ( const cv::Mat &  data)

Definition at line 170 of file Compression.cpp.

cv::Mat rtabmap::compressData2 ( const cv::Mat &  data)

Definition at line 201 of file Compression.cpp.

std::vector< unsigned char > rtabmap::compressImage ( const cv::Mat &  image,
const std::string &  format = ".png" 
)

Definition at line 100 of file Compression.cpp.

cv::Mat rtabmap::compressImage2 ( const cv::Mat &  image,
const std::string &  format = ".png" 
)

Definition at line 120 of file Compression.cpp.

cv::Mat rtabmap::compressString ( const std::string &  str)

Definition at line 277 of file Compression.cpp.

static void rtabmap::computeDescriptors ( const Mat &  image,
std::vector< KeyPoint > &  keypoints,
Mat &  descriptors,
const std::vector< Point > &  pattern,
int  dsize,
int  WTA_K 
)
static

Compute the ORB decriptors

Parameters
imagethe image to compute the features and descriptors on
integral_imagethe integral image of the image (can be empty, but the computation will be slower)
levelthe scale at which we compute the orientation
keypointsthe keypoints to use
descriptorsthe resulting descriptors

Definition at line 716 of file Orb.cpp.

static void rtabmap::computeKeyPoints ( const std::vector< Mat > &  imagePyramid,
const std::vector< Mat > &  maskPyramid,
std::vector< std::vector< KeyPoint > > &  allKeypoints,
int  nfeatures,
int  firstLevel,
double  scaleFactor,
int  edgeThreshold,
int  patchSize,
int  scoreType,
ParametersMap  fastParameters 
)
static

Compute the ORB keypoints on an image

Parameters
image_pyramidthe image pyramid to compute the features and descriptors on
mask_pyramidthe masks to apply at every level
keypointsthe resulting keypoints, clustered per level

Definition at line 621 of file Orb.cpp.

static void rtabmap::computeOrbDescriptor ( const KeyPoint &  kpt,
const Mat &  img,
const Point *  pattern,
uchar *  desc,
int  dsize,
int  WTA_K 
)
static

Definition at line 138 of file Orb.cpp.

static void rtabmap::computeOrientation ( const Mat &  image,
std::vector< KeyPoint > &  keypoints,
int  halfPatchSize,
const std::vector< int > &  umax 
)
static

Compute the ORB keypoint orientations

Parameters
imagethe image to compute the features and descriptors on
integral_imagethe integral image of the iamge (can be empty, but the computation will be slower)
scalethe scale at which we compute the orientation
keypointsthe resulting keypoints

Definition at line 604 of file Orb.cpp.

QIcon rtabmap::createIcon ( const QColor &  color)

Definition at line 1474 of file GraphViewer.cpp.

std::vector<double> rtabmap::cumSum ( const std::vector< double > &  v)

Definition at line 53 of file ParticleFilter.h.

bool rtabmap::databaseRecovery ( const std::string &  corruptedDatabase,
bool  keepCorruptedDatabase = true,
std::string *  errorMsg = 0,
ProgressState progressState = 0 
)

Return true on success. The database is renamed to "*.backup.db" before recovering.

Parameters
corruptedDatabasedatabase to recover
keepCorruptedDatabaseif false and on recovery success, the backup database is removed
errorMsgerror message if the function returns false
progressStateA ProgressState object used to get status of the recovery process

Definition at line 39 of file Recovery.cpp.

double rtabmap::DEG2RAD ( const double  x)
inline

Definition at line 53 of file GeodeticCoords.cpp.

std::shared_ptr<chisel::DepthImage<float> > rtabmap::depthImageToChisel ( const cv::Mat &  image)

Definition at line 27 of file chisel_conversions.h.

template<typename PointT >
void rtabmap::feedImpl ( const std::map< int, typename pcl::PointCloud< PointT >::Ptr > &  clouds,
const std::map< int, pcl::IndicesPtr > &  indices,
const std::multimap< int, Link > &  links,
float  maxCorrespondenceDistance,
double  minOverlap,
double  alpha,
double  beta,
cv::Mat_< double > &  gains,
std::map< int, int > &  idToIndex 
)
void rtabmap::floodfill ( QImage &  image,
const cv::Mat &  depthImage,
int  x,
int  y,
float  lastDepthValue,
float  error 
)

Definition at line 228 of file EditDepthArea.cpp.

static float rtabmap::getScale ( int  level,
int  firstLevel,
double  scaleFactor 
)
inlinestatic

Definition at line 561 of file Orb.cpp.

static void rtabmap::HarrisResponses ( const Mat &  img,
std::vector< KeyPoint > &  pts,
int  blockSize,
float  harris_k 
)
static

Function that computes the Harris responses in a blockSize x blockSize patch at given points in an image

Definition at line 62 of file Orb.cpp.

static float rtabmap::IC_Angle ( const Mat &  image,
const int  half_k,
Point2f  pt,
const std::vector< int > &  u_max 
)
static

Definition at line 106 of file Orb.cpp.

int rtabmap::inFrontOfBothCameras ( const cv::Mat &  x,
const cv::Mat &  xp,
const cv::Mat &  R,
const cv::Mat &  T 
)

Definition at line 132 of file EpipolarGeometry.cpp.

void rtabmap::initFisheyeRectificationMap ( const CameraModel fisheyeModel,
cv::Mat &  mapX,
cv::Mat &  mapY 
)

Definition at line 159 of file CameraTango.cpp.

static void rtabmap::initializeOrbPattern ( const Point *  pattern0,
std::vector< Point > &  pattern,
int  ntuples,
int  tupleSize,
int  poolSize 
)
static

Definition at line 261 of file Orb.cpp.

static void rtabmap::makeRandomPattern ( int  patchSize,
Point *  pattern,
int  npoints 
)
static

Definition at line 549 of file Orb.cpp.

void rtabmap::onFrameAvailableRouter ( void *  context,
TangoCameraId  id,
const TangoImageBuffer *  color 
)

Definition at line 55 of file CameraTango.cpp.

void rtabmap::onPointCloudAvailableRouter ( void *  context,
const TangoPointCloud *  point_cloud 
)

Definition at line 46 of file CameraTango.cpp.

void rtabmap::onPoseAvailableRouter ( void *  context,
const TangoPoseData *  pose 
)

Definition at line 89 of file CameraTango.cpp.

void rtabmap::onTangoEventAvailableRouter ( void *  context,
const TangoEvent *  event 
)

Definition at line 98 of file CameraTango.cpp.

std::ostream & rtabmap::operator<< ( std::ostream &  os,
const Transform s 
)

Definition at line 312 of file Transform.cpp.

template<typename PointRGBT >
chisel::PointCloudPtr rtabmap::pointCloudRGBToChisel ( const typename pcl::PointCloud< PointRGBT > &  cloud,
const Transform transform = Transform::getIdentity() 
)

Definition at line 50 of file chisel_conversions.h.

template<typename PointT >
chisel::PointCloudPtr rtabmap::pointCloudToChisel ( const typename pcl::PointCloud< PointT > &  cloud,
const Transform transform = Transform::getIdentity() 
)

Definition at line 84 of file chisel_conversions.h.

double rtabmap::RAD2DEG ( const double  x)
inline

Definition at line 54 of file GeodeticCoords.cpp.

std::vector<double> rtabmap::resample ( const std::vector< double > &  p,
const std::vector< double > &  w,
bool  normalizeWeights = false 
)

Definition at line 65 of file ParticleFilter.h.

Eigen::Vector3f rtabmap::rotatePointAroundAxe ( const Eigen::Vector3f &  point,
const Eigen::Vector3f &  axis,
float  angle 
)

Definition at line 2807 of file CloudViewer.cpp.

rtabmap::RTABMAP_DEPRECATED ( typedef SensorData  Image,
"rtabmap::Image class is renamed to rtabmap::SensorData  ,
use the last one instead."   
)
bool rtabmap::sortCallback ( const std::string &  a,
const std::string &  b 
)

Definition at line 3308 of file PreferencesDialog.cpp.

double rtabmap::sqr ( uchar  v)

Definition at line 41 of file GainCompensator.cpp.

double rtabmap::square ( const double &  value)
inline

Definition at line 55 of file GeodeticCoords.cpp.

bool rtabmap::testAABBAABB ( const AABB a,
const AABB b 
)

Definition at line 110 of file GainCompensator.cpp.

cv::Mat rtabmap::uncompressData ( const cv::Mat &  bytes)

Definition at line 231 of file Compression.cpp.

cv::Mat rtabmap::uncompressData ( const std::vector< unsigned char > &  bytes)

Definition at line 237 of file Compression.cpp.

cv::Mat rtabmap::uncompressData ( const unsigned char *  bytes,
unsigned long  size 
)

Definition at line 242 of file Compression.cpp.

cv::Mat rtabmap::uncompressImage ( const cv::Mat &  bytes)

Definition at line 130 of file Compression.cpp.

cv::Mat rtabmap::uncompressImage ( const std::vector< unsigned char > &  bytes)

Definition at line 152 of file Compression.cpp.

std::string rtabmap::uncompressString ( const cv::Mat &  bytes)

Definition at line 283 of file Compression.cpp.

rtabmap::vtkStandardNewMacro ( CloudViewerInteractorStyle  )
rtabmap::vtkStandardNewMacro ( CloudViewerCellPicker  )
rtabmap::vtkStandardNewMacro ( vtkImageMatSource  )

Variable Documentation

int rtabmap::bit_pattern_31_[256 *4]
static

Definition at line 288 of file Orb.cpp.

const int rtabmap::frustum_indices[]
static
Initial value:
= {
1, 2, 3, 4, 1, 0, 2, 0, 3, 0, 4}

Definition at line 1674 of file CloudViewer.cpp.

const float rtabmap::frustum_vertices[]
static
Initial value:
= {
0.0f, 0.0f, 0.0f,
1.0f, 1.0f, 1.0f,
1.0f, -1.0f, 1.0f,
1.0f, -1.0f, -1.0f,
1.0f, 1.0f, -1.0f}

Definition at line 1667 of file CloudViewer.cpp.

const float rtabmap::HARRIS_K = 0.04f

Definition at line 55 of file Orb.cpp.

const int rtabmap::holeSize = 5

Definition at line 41 of file CameraTango.cpp.

const int rtabmap::kVersionStringLength = 128

Definition at line 40 of file CameraTango.cpp.

const float rtabmap::maxDepthError = 0.10

Definition at line 42 of file CameraTango.cpp.

rtabmap::Transform rtabmap::opticalRotation(1.0f, 0.0f, 0.0f, 0.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f,-1.0f, 0.0f)
static
const int rtabmap::scanDownsampling = 1

Definition at line 43 of file CameraTango.cpp.



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