|
static void | addGradientDescentStep (float q0, float q1, float q2, float q3, float _2dx, float _2dy, float _2dz, float mx, float my, float mz, float &s0, float &s1, float &s2, float &s3) |
|
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) |
|
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 | computeDescriptors (const Mat &image, vector< KeyPoint > &keypoints, Mat &descriptors, const vector< Point > &pattern) |
|
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) |
|
static void | computeOrbDescriptor (const KeyPoint &kpt, const Mat &img, const Point *pattern, uchar *desc, int dsize, int WTA_K) |
|
static bool | computeOrientation (Eigen::Vector3f A, Eigen::Vector3f E, Eigen::Quaternionf &orientation) |
|
static bool | computeOrientation (Eigen::Vector3f A, Eigen::Quaternionf &orientation) |
|
static void | computeOrientation (const Mat &image, vector< KeyPoint > &keypoints, const vector< int > &umax, int halfPatchSize) |
|
static void | computeOrientation (const Mat &image, std::vector< KeyPoint > &keypoints, int halfPatchSize, const std::vector< int > &umax) |
|
void | copyCameraConfig (const ArSession *ar_session, const ArCameraConfigList *all_configs, int index, int num_configs, CameraConfig *camera_config) |
|
QIcon | createIcon (const QColor &color) |
|
static void | crossProduct (T ax, T ay, T az, T bx, T by, T bz, T &rx, T &ry, T &rz) |
|
std::vector< double > | cumSum (const std::vector< double > &v) |
|
void | cvStereoRectifyFisheye (const CvMat *_cameraMatrix1, const CvMat *_cameraMatrix2, const CvMat *_distCoeffs1, const CvMat *_distCoeffs2, CvSize imageSize, const CvMat *matR, const CvMat *matT, CvMat *_R1, CvMat *_R2, CvMat *_P1, CvMat *_P2, CvMat *matQ, int flags, double alpha, CvSize newImgSize) |
|
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) |
|
void | destroyCameraConfigs (std::vector< CameraConfig > &camera_configs) |
|
PointMatcher< T >::TransformationParameters | eigenMatrixToDim (const typename PointMatcher< T >::TransformationParameters &matrix, int dimp1) |
|
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 (QRgb *bits, const cv::Mat &depthImage, int x, int y, float lastDepthValue, float error, int &iterations) |
|
ScreenRotation | GetAndroidRotationFromColorCameraToDisplay (ScreenRotation display_rotation, int color_camera_rotation) |
|
ScreenRotation | GetAndroidRotationFromColorCameraToDisplay (int display_rotation, int color_camera_rotation) |
|
void | getCameraConfigLowestAndHighestResolutions (std::vector< CameraConfig > &camera_configs, CameraConfig **lowest_resolution_config, CameraConfig **highest_resolution_config) |
|
Transform | getMeanVelocity (const std::list< std::pair< std::vector< float >, double > > &transforms) |
|
std::string | getPDALSupportedWriters () |
|
static float | getScale (int level, int firstLevel, double scaleFactor) |
|
glm::mat4 | glmFromTransform (const rtabmap::Transform &transform) |
|
rtabmap::Transform | glmToTransform (const glm::mat4 &mat) |
|
static void | HarrisResponses (const Mat &img, std::vector< KeyPoint > &pts, int blockSize, float harris_k) |
|
static float | IC_Angle (const Mat &image, Point2f pt, const vector< int > &u_max, int halfPatchSize) |
|
static float | IC_Angle (const Mat &image, const int half_k, Point2f pt, const std::vector< int > &u_max) |
|
rtabmap::Transform | icpCC (const pcl::PointCloud< pcl::PointXYZI >::Ptr &fromCloud, pcl::PointCloud< pcl::PointXYZI >::Ptr &toCloud, int maxIterations=150, double minRMSDecrease=0.00001, bool force3DoF=false, bool force4DoF=false, int samplingLimit=50000, double finalOverlapRatio=0.85, bool filterOutFarthestPoints=false, double maxFinalRMS=0.2, float *finalRMS=0, std::string *errorMsg=0) |
|
void | icvGetRectanglesFisheye (const CvMat *cameraMatrix, const CvMat *distCoeffs, const CvMat *R, const CvMat *newCameraMatrix, CvSize imgSize, cv::Rect_< float > &inner, cv::Rect_< float > &outer) |
|
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) |
|
void | invertQuaternion (double q0, double q1, double q2, double q3, double &q0_inv, double &q1_inv, double &q2_inv, double &q3_inv) |
|
static float | invSqrt (float x) |
|
rtabmap::LaserScan | laserScanFromDP (const DP &cloud, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity()) |
|
DP | laserScanToDP (const rtabmap::LaserScan &scan, bool ignoreLocalTransform=false) |
|
static void | makeRandomPattern (int patchSize, Point *pattern, int npoints) |
|
void | NMS (const std::vector< cv::KeyPoint > &ptsIn, const cv::Mat &conf, const cv::Mat &descriptorsIn, std::vector< cv::KeyPoint > &ptsOut, cv::Mat &descriptorsOut, int border, int dist_thresh, int img_width, int img_height) |
|
int | NormalizedColorCameraRotation (int camera_rotation) |
|
static void | normalizeQuaternion (T &q0, T &q1, T &q2, T &q3) |
|
void | normalizeQuaternion (double &q0, double &q1, double &q2, double &q3) |
|
static T | normalizeVector (T &vx, T &vy, T &vz) |
|
void | normalizeVector (double &x, double &y, double &z) |
|
static void | normalizeVectorOpt (T &vx, T &vy, T &vz) |
|
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 StereoCameraModel &model) |
|
RTABMAP_EXP std::ostream & | operator<< (std::ostream &os, const Transform &s) |
|
RTABMAP_EXP std::ostream & | operator<< (std::ostream &os, const CameraModel &model) |
|
static void | orientationChangeFromGyro (float q0, float q1, float q2, float q3, float gx, float gy, float gz, float &qDot1, float &qDot2, float &qDot3, float &qDot4) |
|
void | pclFromDP (const DP &cloud, pcl::PointCloud< pcl::PointXYZINormal > &pclCloud) |
|
void | pclFromDP (const DP &cloud, pcl::PointCloud< pcl::PointXYZI > &pclCloud) |
|
DP | pclToDP (const pcl::PointCloud< pcl::PointXYZI >::Ptr &pclCloud, bool is2D) |
|
DP | pclToDP (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &pclCloud, bool is2D) |
|
chisel::PointCloudPtr | pointCloudRGBToChisel (const typename pcl::PointCloud< PointRGBT > &cloud, const Transform &transform=Transform::getIdentity()) |
|
chisel::PointCloudPtr | pointCloudToChisel (const typename pcl::PointCloud< PointT > &cloud, const Transform &transform=Transform::getIdentity()) |
|
void | quaternionMultiplication (double p0, double p1, double p2, double p3, double q0, double q1, double q2, double q3, double &r0, double &r1, double &r2, double &r3) |
|
double | RAD2DEG (const double x) |
|
std::vector< double > | resample (const std::vector< double > &p, const std::vector< double > &w, bool normalizeWeights=false) |
|
static void | rotateAndScaleVector (float q0, float q1, float q2, float q3, float _2dx, float _2dy, float _2dz, float &rx, float &ry, float &rz) |
|
Eigen::Vector3f | rotatePointAroundAxe (const Eigen::Vector3f &point, const Eigen::Vector3f &axis, float angle) |
|
void | rotateVectorByQuaternion (double x, double y, double z, double q0, double q1, double q2, double q3, double &vx, double &vy, double &vz) |
|
| RTABMAP_DEPRECATED (typedef SensorData Image, "rtabmap::Image class is renamed to rtabmap::SensorData, use the last one instead.") |
|
int | savePDALFile (const std::string &filePath, const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::vector< int > &cameraIds=std::vector< int >(), bool binary=false, const std::vector< float > &intensities=std::vector< float >()) |
|
int | savePDALFile (const std::string &filePath, const pcl::PointCloud< pcl::PointXYZINormal > &cloud, const std::vector< int > &cameraIds=std::vector< int >(), bool binary=false) |
|
int | savePDALFile (const std::string &filePath, const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const std::vector< int > &cameraIds=std::vector< int >(), bool binary=false, const std::vector< float > &intensities=std::vector< float >()) |
|
int | savePDALFile (const std::string &filePath, const pcl::PointCloud< pcl::PointXYZ > &cloud, const std::vector< int > &cameraIds=std::vector< int >(), bool binary=false) |
|
int | savePDALFile (const std::string &filePath, const pcl::PointCloud< pcl::PointXYZI > &cloud, const std::vector< int > &cameraIds=std::vector< int >(), bool binary=false) |
|
void | scaleQuaternion (double gain, double &dq0, double &dq1, double &dq2, double &dq3) |
|
bool | sortCallback (const std::string &a, const std::string &b) |
|
double | sqr (uchar v) |
|
double | square (const double &value) |
|
void | stereoRectifyFisheye (cv::InputArray _cameraMatrix1, cv::InputArray _distCoeffs1, cv::InputArray _cameraMatrix2, cv::InputArray _distCoeffs2, cv::Size imageSize, cv::InputArray _Rmat, cv::InputArray _Tmat, cv::OutputArray _Rmat1, cv::OutputArray _Rmat2, cv::OutputArray _Pmat1, cv::OutputArray _Pmat2, cv::OutputArray _Qmat, int flags, double alpha, cv::Size newImageSize) |
|
bool | testAABBAABB (const AABB &a, const AABB &b) |
|
cv::Mat RTABMAP_EXP | uncompressData (const unsigned char *bytes, unsigned long size) |
|
cv::Mat RTABMAP_EXP | uncompressData (const std::vector< unsigned char > &bytes) |
|
cv::Mat RTABMAP_EXP | uncompressData (const cv::Mat &bytes) |
|
cv::Mat RTABMAP_EXP | uncompressImage (const std::vector< unsigned char > &bytes) |
|
cv::Mat RTABMAP_EXP | uncompressImage (const cv::Mat &bytes) |
|
std::string RTABMAP_EXP | uncompressString (const cv::Mat &bytes) |
|
| vtkStandardNewMacro (vtkImageMatSource) |
|
| vtkStandardNewMacro (CloudViewerCellPicker) |
|
| vtkStandardNewMacro (CloudViewerInteractorStyle) |
|