Namespaces | |
namespace | graph |
namespace | util2d |
namespace | util3d |
Classes | |
class | AboutDialog |
class | BayesFilter |
class | BRISK |
class | CalibrationDialog |
class | Camera |
class | CameraEvent |
class | CameraFreenect |
class | CameraFreenect2 |
class | CameraImages |
class | CameraInfo |
class | CameraModel |
class | CameraOpenni |
class | CameraOpenNI2 |
class | CameraOpenNICV |
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 | CompressionThread |
class | ConsoleWidget |
class | CreateSimpleCalibrationDialog |
class | CV_ORB |
class | DatabaseViewer |
class | DataRecorder |
class | DBDriver |
class | DBDriverSqlite3 |
class | DBReader |
class | EpipolarGeometry |
class | ExportCloudsDialog |
class | ExportDialog |
class | ExportScansDialog |
class | FAST |
class | FAST_BRIEF |
class | FAST_FREAK |
class | Feature2D |
class | FlannIndex |
class | GeodeticCoords |
class | GFTT |
class | GFTT_BRIEF |
class | GFTT_FREAK |
class | GFTT_ORB |
class | GraphViewer |
class | ImageView |
class | KeypointItem |
class | LineItem |
class | Link |
class | LinkItem |
class | LoopClosureViewer |
class | MainWindow |
class | MapVisibilityWidget |
class | Memory |
class | MyInteractorStyle |
class | NodeItem |
class | OctoMap |
class | OcTreeNodeInfo |
class | Odometry |
class | OdometryEvent |
class | OdometryF2F |
class | OdometryF2M |
class | OdometryInfo |
class | OdometryMono |
class | OdometryResetEvent |
class | OdometryThread |
class | OdometryViewer |
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 | Registration |
class | RegistrationIcp |
class | RegistrationInfo |
class | RegistrationVis |
class | Rtabmap |
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 | Transform |
class | UserDataEvent |
class | VisualWord |
class | VWDictionary |
class | WeightAgeIdKey |
Typedefs | |
typedef std::map< std::string, std::string > | ParametersMap |
typedef std::pair< std::string, std::string > | ParametersPair |
Functions | |
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") |
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) |
double | DEG2RAD (const double x) |
static float | getScale (int level, int firstLevel, double scaleFactor) |
static void | HarrisResponses (const Mat &img, std::vector< KeyPoint > &pts, int blockSize, float harris_k) |
void | HSVtoRGB (float *r, float *g, float *b, float h, float s, float v) |
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) |
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 TangoXYZij *xyz_ij) |
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) |
bool | removeDirRecursively (const QString &dirName) |
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.") | |
double | square (const double &value) |
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) |
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 = 10 |
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) |
File from OpenCV (see License below), modified by Mathieu Labbe 2016
typedef std::map<std::string, std::string> rtabmap::ParametersMap |
Definition at line 40 of file Parameters.h.
typedef std::pair<std::string, std::string> rtabmap::ParametersPair |
Definition at line 41 of file Parameters.h.
std::vector< unsigned char > rtabmap::compressData | ( | const cv::Mat & | data | ) |
Definition at line 152 of file Compression.cpp.
cv::Mat rtabmap::compressData2 | ( | const cv::Mat & | data | ) |
Definition at line 183 of file Compression.cpp.
std::vector< unsigned char > rtabmap::compressImage | ( | const cv::Mat & | image, |
const std::string & | format = ".png" |
||
) |
Definition at line 86 of file Compression.cpp.
cv::Mat rtabmap::compressImage2 | ( | const cv::Mat & | image, |
const std::string & | format = ".png" |
||
) |
Definition at line 106 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
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 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] |
static void rtabmap::computeOrbDescriptor | ( | const KeyPoint & | kpt, |
const Mat & | img, | ||
const Point * | pattern, | ||
uchar * | desc, | ||
int | dsize, | ||
int | WTA_K | ||
) | [static] |
static void rtabmap::computeOrientation | ( | const Mat & | image, |
std::vector< KeyPoint > & | keypoints, | ||
int | halfPatchSize, | ||
const std::vector< int > & | umax | ||
) | [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 |
QIcon rtabmap::createIcon | ( | const QColor & | color | ) |
Definition at line 1220 of file GraphViewer.cpp.
std::vector<double> rtabmap::cumSum | ( | const std::vector< double > & | v | ) |
Definition at line 53 of file ParticleFilter.h.
double rtabmap::DEG2RAD | ( | const double | x | ) | [inline] |
Definition at line 53 of file GeodeticCoords.cpp.
static float rtabmap::getScale | ( | int | level, |
int | firstLevel, | ||
double | scaleFactor | ||
) | [inline, static] |
static void rtabmap::HarrisResponses | ( | const Mat & | img, |
std::vector< KeyPoint > & | pts, | ||
int | blockSize, | ||
float | harris_k | ||
) | [static] |
void rtabmap::HSVtoRGB | ( | float * | r, |
float * | g, | ||
float * | b, | ||
float | h, | ||
float | s, | ||
float | v | ||
) |
Definition at line 303 of file OctoMap.cpp.
static float rtabmap::IC_Angle | ( | const Mat & | image, |
const int | half_k, | ||
Point2f | pt, | ||
const std::vector< int > & | u_max | ||
) | [static] |
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.
static void rtabmap::initializeOrbPattern | ( | const Point * | pattern0, |
std::vector< Point > & | pattern, | ||
int | ntuples, | ||
int | tupleSize, | ||
int | poolSize | ||
) | [static] |
static void rtabmap::makeRandomPattern | ( | int | patchSize, |
Point * | pattern, | ||
int | npoints | ||
) | [static] |
void rtabmap::onFrameAvailableRouter | ( | void * | context, |
TangoCameraId | id, | ||
const TangoImageBuffer * | color | ||
) |
Definition at line 50 of file CameraTango.cpp.
void rtabmap::onPointCloudAvailableRouter | ( | void * | context, |
const TangoXYZij * | xyz_ij | ||
) |
Definition at line 44 of file CameraTango.cpp.
void rtabmap::onPoseAvailableRouter | ( | void * | context, |
const TangoPoseData * | pose | ||
) |
Definition at line 77 of file CameraTango.cpp.
void rtabmap::onTangoEventAvailableRouter | ( | void * | context, |
const TangoEvent * | event | ||
) |
Definition at line 83 of file CameraTango.cpp.
std::ostream & rtabmap::operator<< | ( | std::ostream & | os, |
const Transform & | s | ||
) |
Definition at line 279 of file Transform.cpp.
bool rtabmap::removeDirRecursively | ( | const QString & | dirName | ) |
Definition at line 497 of file ExportCloudsDialog.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 1769 of file CloudViewer.cpp.
rtabmap::RTABMAP_DEPRECATED | ( | typedef SensorData | Image, |
"rtabmap::Image class is renamed to rtabmap::SensorData | , | ||
use the last one instead." | |||
) |
double rtabmap::square | ( | const double & | value | ) | [inline] |
Definition at line 54 of file GeodeticCoords.cpp.
cv::Mat rtabmap::uncompressData | ( | const cv::Mat & | bytes | ) |
Definition at line 213 of file Compression.cpp.
cv::Mat rtabmap::uncompressData | ( | const std::vector< unsigned char > & | bytes | ) |
Definition at line 219 of file Compression.cpp.
cv::Mat rtabmap::uncompressData | ( | const unsigned char * | bytes, |
unsigned long | size | ||
) |
Definition at line 224 of file Compression.cpp.
cv::Mat rtabmap::uncompressImage | ( | const cv::Mat & | bytes | ) |
Definition at line 116 of file Compression.cpp.
cv::Mat rtabmap::uncompressImage | ( | const std::vector< unsigned char > & | bytes | ) |
Definition at line 134 of file Compression.cpp.
int rtabmap::bit_pattern_31_[256 *4] [static] |
const int rtabmap::frustum_indices[] [static] |
{ 1, 2, 3, 4, 1, 0, 2, 0, 3, 0, 4}
Definition at line 982 of file CloudViewer.cpp.
const float rtabmap::frustum_vertices[] [static] |
{ 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 975 of file CloudViewer.cpp.
const float rtabmap::HARRIS_K = 0.04f |
const int rtabmap::holeSize = 10 |
Definition at line 40 of file CameraTango.cpp.
const int rtabmap::kVersionStringLength = 128 |
Definition at line 39 of file CameraTango.cpp.
const float rtabmap::maxDepthError = 0.10 |
Definition at line 41 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] |