Namespaces | |
graph | |
util2d | |
util3d | |
Typedefs | |
typedef std::map< EnvSensor::Type, EnvSensor > | EnvSensors |
typedef std::map< int, Landmark > | Landmarks |
typedef std::map< std::string, std::string > | ParametersMap |
typedef std::pair< std::string, std::string > | ParametersPair |
Enumerations | |
enum | ScreenRotation { ROTATION_IGNORED = -1, ROTATION_0 = 0, ROTATION_90 = 1, ROTATION_180 = 2, ROTATION_270 = 3 } |
Functions | |
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) |
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 | 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) |
template<typename T > | |
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) |
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 (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) |
static float | getScale (int level, int firstLevel, double scaleFactor) |
std::string | getTraceback () |
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) |
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) |
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) |
template<typename T > | |
static void | normalizeQuaternion (T &q0, T &q1, T &q2, T &q3) |
void | normalizeQuaternion (double &q0, double &q1, double &q2, double &q3) |
template<typename T > | |
static T | normalizeVector (T &vx, T &vy, T &vz) |
void | normalizeVector (double &x, double &y, double &z) |
template<typename T > | |
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) |
static const rtabmap::Transform | opengl_world_T_rtabmap_world (0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f) |
static const rtabmap::Transform | opengl_world_T_tango_world (1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f,-1.0f, 0.0f, 0.0f) |
RTABMAP_EXP std::ostream & | operator<< (std::ostream &os, const CameraModel &model) |
RTABMAP_EXP std::ostream & | operator<< (std::ostream &os, const Transform &s) |
static const rtabmap::Transform | optical_T_opengl (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 void | orientationChangeFromGyro (float q0, float q1, float q2, float q3, float gx, float gy, float gz, float &qDot1, float &qDot2, float &qDot3, float &qDot4) |
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()) |
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.") | |
static const rtabmap::Transform | rtabmap_world_T_opengl_world (0.0f, 0.0f,-1.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f) |
static const rtabmap::Transform | rtabmap_world_T_tango_world (0.0f, 1.0f, 0.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f) |
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) |
static const rtabmap::Transform | tango_device_T_rtabmap_world (0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f) |
static const rtabmap::Transform | tango_world_T_rtabmap_world (0.0f,-1.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f) |
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 int | bit_pattern_31_ [256 *4] |
const int | c1 = 64 |
const int | c2 = 64 |
const int | c3 = 128 |
const int | c4 = 128 |
const int | c5 = 256 |
const int | d1 = 256 |
const float | factorPI = (float)(CV_PI/180.f) |
static const int | frustum_indices [] |
static const float | frustum_vertices [] |
static PythonSingleTon | g_python |
const float | HARRIS_K = 0.04f |
const int | holeSize = 5 |
const int | kVersionStringLength = 128 |
const float | maxDepthError = 0.10 |
const int | scanDownsampling = 1 |
Contributed by e-consystemgit https://www.e-consystems.com/opensource-linux-webcam-software-application.asp
File from OpenCV (see License below), modified by Mathieu Labbe 2016
This code is a version of ORB from OpenCV but modified by ORB_SLAM2 project to use an OcTree on keypoint detection. This code is licensed under GPLv3 and BSD licenses. If you cannot comply to those licenses, please set WITH_ORB_OCTREE=OFF when building RTAB-Map so that it is not included in the compiled binary. This file is part of ORB-SLAM2.
Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at="" unizar="" dot="" es>=""> (University of Zaragoza) For more information see https://github.com/raulmur/ORB_SLAM2
ORB-SLAM2 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.
ORB-SLAM2 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
You should have received a copy of the GNU General Public License along with ORB-SLAM2. If not, see http://www.gnu.org/licenses/.
Adapted from EdgeSE3Gravity
Adapted code from HDL graph slam: https://github.com/koide3/hdl_graph_slam/blob/master/include/g2o/edge_se3_priorvec.hpp
Author: Mathieu Labbe This file is a copy of GPSPose2Factor.h of gtsam examples A simple 2D 'GPS' like factor The factor contains a X-Y position measurement (mx, my) for a Pose, but no rotation information The error vector will be [x-mx, y-my]'
Author: Mathieu Labbe This file is a copy of GPSPose2Factor.h of gtsam examples for Pose3 A simple 3D 'GPS' like factor The factor contains a X-Y-Z position measurement (mx, my, mz) for a Pose, but no rotation information The error vector will be [x-mx, y-my, z-mz]'
Python interface for python matchers like:
Original code from https://github.com/KinglittleQ/SuperPoint_SLAM
typedef std::map<EnvSensor::Type, EnvSensor> rtabmap::EnvSensors |
Definition at line 81 of file EnvSensor.h.
typedef std::map<int, Landmark> rtabmap::Landmarks |
Definition at line 72 of file Landmark.h.
typedef std::map<std::string, std::string> rtabmap::ParametersMap |
Definition at line 43 of file Parameters.h.
typedef std::pair<std::string, std::string> rtabmap::ParametersPair |
Definition at line 44 of file Parameters.h.
|
inlinestatic |
Definition at line 97 of file MadgwickFilter.cpp.
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 237 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 130 of file CameraTango.cpp.
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 |
Compute the ORB decriptors
image | the image to compute the features and descriptors on |
integral_image | the integral image of the image (can be empty, but the computation will be slower) |
level | the scale at which we compute the orientation |
keypoints | the keypoints to use |
descriptors | the resulting descriptors |
|
static |
Definition at line 1041 of file ORBextractor.cc.
|
static |
|
static |
Definition at line 114 of file ORBextractor.cc.
|
static |
|
inlinestatic |
Definition at line 151 of file MadgwickFilter.cpp.
|
inlinestatic |
Definition at line 211 of file MadgwickFilter.cpp.
|
static |
Definition at line 479 of file ORBextractor.cc.
|
static |
Compute the ORB keypoint orientations
image | the image to compute the features and descriptors on |
integral_image | the integral image of the iamge (can be empty, but the computation will be slower) |
scale | the scale at which we compute the orientation |
keypoints | the resulting keypoints |
void rtabmap::copyCameraConfig | ( | const ArSession * | ar_session, |
const ArCameraConfigList * | all_configs, | ||
int | index, | ||
int | num_configs, | ||
CameraConfig * | camera_config | ||
) |
Definition at line 104 of file CameraARCore.cpp.
QIcon rtabmap::createIcon | ( | const QColor & | color | ) |
Definition at line 1540 of file GraphViewer.cpp.
|
inlinestatic |
Definition at line 131 of file MadgwickFilter.cpp.
std::vector<double> rtabmap::cumSum | ( | const std::vector< double > & | v | ) |
Definition at line 53 of file ParticleFilter.h.
void rtabmap::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 | ||
) |
Definition at line 971 of file stereoRectifyFisheye.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.
corruptedDatabase | database to recover |
keepCorruptedDatabase | if false and on recovery success, the backup database is removed |
errorMsg | error message if the function returns false |
progressState | A ProgressState object used to get status of the recovery process |
Definition at line 39 of file Recovery.cpp.
|
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.
void rtabmap::destroyCameraConfigs | ( | std::vector< CameraConfig > & | camera_configs | ) |
Definition at line 120 of file CameraARCore.cpp.
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 | ||
) |
Definition at line 124 of file GainCompensator.cpp.
void rtabmap::floodfill | ( | QRgb * | bits, |
const cv::Mat & | depthImage, | ||
int | x, | ||
int | y, | ||
float | lastDepthValue, | ||
float | error, | ||
int & | iterations | ||
) |
Definition at line 288 of file EditDepthArea.cpp.
|
inline |
|
inline |
void rtabmap::getCameraConfigLowestAndHighestResolutions | ( | std::vector< CameraConfig > & | camera_configs, |
CameraConfig ** | lowest_resolution_config, | ||
CameraConfig ** | highest_resolution_config | ||
) |
Definition at line 72 of file CameraARCore.cpp.
Transform rtabmap::getMeanVelocity | ( | const std::list< std::pair< std::vector< float >, double > > & | transforms | ) |
Definition at line 252 of file Odometry.cpp.
|
inlinestatic |
std::string rtabmap::getTraceback | ( | ) |
Definition at line 33 of file PyMatcher.cpp.
|
inline |
|
inline |
|
static |
|
static |
Definition at line 83 of file ORBextractor.cc.
|
static |
void rtabmap::icvGetRectanglesFisheye | ( | const CvMat * | cameraMatrix, |
const CvMat * | distCoeffs, | ||
const CvMat * | R, | ||
const CvMat * | newCameraMatrix, | ||
CvSize | imgSize, | ||
cv::Rect_< float > & | inner, | ||
cv::Rect_< float > & | outer | ||
) |
Definition at line 926 of file stereoRectifyFisheye.h.
int rtabmap::inFrontOfBothCameras | ( | const cv::Mat & | x, |
const cv::Mat & | xp, | ||
const cv::Mat & | R, | ||
const cv::Mat & | T | ||
) |
Definition at line 138 of file EpipolarGeometry.cpp.
void rtabmap::initFisheyeRectificationMap | ( | const CameraModel & | fisheyeModel, |
cv::Mat & | mapX, | ||
cv::Mat & | mapY | ||
) |
Definition at line 151 of file CameraTango.cpp.
|
static |
void rtabmap::invertQuaternion | ( | double | q0, |
double | q1, | ||
double | q2, | ||
double | q3, | ||
double & | q0_inv, | ||
double & | q1_inv, | ||
double & | q2_inv, | ||
double & | q3_inv | ||
) |
Definition at line 420 of file ComplementaryFilter.cpp.
|
inlinestatic |
Definition at line 33 of file MadgwickFilter.cpp.
|
static |
void rtabmap::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 | ||
) |
Definition at line 264 of file SuperPoint.cc.
|
inline |
|
inlinestatic |
Definition at line 58 of file MadgwickFilter.cpp.
void rtabmap::normalizeQuaternion | ( | double & | q0, |
double & | q1, | ||
double & | q2, | ||
double & | q3 | ||
) |
Definition at line 411 of file ComplementaryFilter.cpp.
|
inlinestatic |
Definition at line 141 of file MadgwickFilter.cpp.
void rtabmap::normalizeVector | ( | double & | x, |
double & | y, | ||
double & | z | ||
) |
Definition at line 402 of file ComplementaryFilter.cpp.
|
inlinestatic |
Definition at line 49 of file MadgwickFilter.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.
|
static |
|
static |
std::ostream & rtabmap::operator<< | ( | std::ostream & | os, |
const CameraModel & | model | ||
) |
Definition at line 768 of file CameraModel.cpp.
std::ostream & rtabmap::operator<< | ( | std::ostream & | os, |
const Transform & | s | ||
) |
Definition at line 333 of file Transform.cpp.
|
static |
|
inlinestatic |
Definition at line 84 of file MadgwickFilter.cpp.
chisel::PointCloudPtr rtabmap::pointCloudRGBToChisel | ( | const typename pcl::PointCloud< PointRGBT > & | cloud, |
const Transform & | transform = Transform::getIdentity() |
||
) |
Definition at line 50 of file chisel_conversions.h.
chisel::PointCloudPtr rtabmap::pointCloudToChisel | ( | const typename pcl::PointCloud< PointT > & | cloud, |
const Transform & | transform = Transform::getIdentity() |
||
) |
Definition at line 84 of file chisel_conversions.h.
void rtabmap::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 | ||
) |
Definition at line 458 of file ComplementaryFilter.cpp.
|
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.
|
inlinestatic |
Definition at line 67 of file MadgwickFilter.cpp.
Eigen::Vector3f rtabmap::rotatePointAroundAxe | ( | const Eigen::Vector3f & | point, |
const Eigen::Vector3f & | axis, | ||
float | angle | ||
) |
Definition at line 3383 of file CloudViewer.cpp.
void rtabmap::rotateVectorByQuaternion | ( | double | x, |
double | y, | ||
double | z, | ||
double | q0, | ||
double | q1, | ||
double | q2, | ||
double | q3, | ||
double & | vx, | ||
double & | vy, | ||
double & | vz | ||
) |
Definition at line 470 of file ComplementaryFilter.cpp.
rtabmap::RTABMAP_DEPRECATED | ( | typedef SensorData | Image, |
"rtabmap::Image class is renamed to rtabmap::SensorData | , | ||
use the last one instead." | |||
) |
|
static |
|
static |
void rtabmap::scaleQuaternion | ( | double | gain, |
double & | dq0, | ||
double & | dq1, | ||
double & | dq2, | ||
double & | dq3 | ||
) |
Definition at line 431 of file ComplementaryFilter.cpp.
bool rtabmap::sortCallback | ( | const std::string & | a, |
const std::string & | b | ||
) |
Definition at line 3758 of file PreferencesDialog.cpp.
double rtabmap::sqr | ( | uchar | v | ) |
Definition at line 41 of file GainCompensator.cpp.
|
inline |
Definition at line 55 of file GeodeticCoords.cpp.
void rtabmap::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 | ||
) |
Definition at line 1181 of file stereoRectifyFisheye.h.
|
static |
|
static |
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 | ) |
|
static |
Definition at line 156 of file ORBextractor.cc.
const int rtabmap::c1 = 64 |
Definition at line 15 of file SuperPoint.cc.
const int rtabmap::c2 = 64 |
Definition at line 16 of file SuperPoint.cc.
const int rtabmap::c3 = 128 |
Definition at line 17 of file SuperPoint.cc.
const int rtabmap::c4 = 128 |
Definition at line 18 of file SuperPoint.cc.
const int rtabmap::c5 = 256 |
Definition at line 19 of file SuperPoint.cc.
const int rtabmap::d1 = 256 |
Definition at line 20 of file SuperPoint.cc.
const float rtabmap::factorPI = (float)(CV_PI/180.f) |
Definition at line 113 of file ORBextractor.cc.
|
static |
Definition at line 1967 of file CloudViewer.cpp.
|
static |
Definition at line 1960 of file CloudViewer.cpp.
|
static |
Definition at line 31 of file PyMatcher.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.
const int rtabmap::scanDownsampling = 1 |
Definition at line 43 of file CameraTango.cpp.