#include "node.h"
#include "features.h"
#include "transformation_estimation_euclidean.h"
#include "transformation_estimation.h"
#include <cmath>
#include "scoped_timer.h"
#include <Eigen/Geometry>
#include <pcl/common/transformation_from_correspondences.h>
#include <fstream>
#include "misc.h"
#include "misc2.h"
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/impl/voxel_grid.hpp>
#include <opencv/highgui.h>
#include <string>
#include <iostream>
Go to the source code of this file.
Functions |
void | copy_filter_cloud (const Eigen::Vector3f ¢er, float radius, const Node *old_node, Node *clone) |
void | copy_filter_features (const Eigen::Vector3f ¢er, float radius, const Node *old_node, Node *clone) |
bool | isNearer (const cv::DMatch &m1, const cv::DMatch &m2) |
static void | keepStrongestMatches (int n, std::vector< cv::DMatch > *matches) |
void | pairwiseObservationLikelihood (const Node *newer_node, const Node *older_node, MatchingResult &mr) |
void | removeDepthless (std::vector< cv::KeyPoint > &feature_locations_2d, const cv::Mat &depth) |
std::vector< cv::DMatch > | sample_matches (unsigned int sample_size, std::vector< cv::DMatch > &matches_with_depth) |
| Randomly choose <sample_size> of the matches.
|
std::vector< cv::DMatch > | sample_matches_prefer_by_distance (unsigned int sample_size, std::vector< cv::DMatch > &matches_with_depth) |
| Randomly choose <sample_size> of the matches.
|
void | squareroot_descriptor_space (cv::Mat &descriptors) |
| Compute the RootSIFT from SIFT according to Arandjelovic and Zisserman.
|
Function Documentation
bool isNearer |
( |
const cv::DMatch & |
m1, |
|
|
const cv::DMatch & |
m2 |
|
) |
| |
void removeDepthless |
( |
std::vector< cv::KeyPoint > & |
feature_locations_2d, |
|
|
const cv::Mat & |
depth |
|
) |
| |
std::vector<cv::DMatch> sample_matches |
( |
unsigned int |
sample_size, |
|
|
std::vector< cv::DMatch > & |
matches_with_depth |
|
) |
| |
Randomly choose <sample_size> of the matches.
Definition at line 1048 of file node.cpp.
Randomly choose <sample_size> of the matches.
Definition at line 1022 of file node.cpp.
Compute the RootSIFT from SIFT according to Arandjelovic and Zisserman.
Definition at line 1555 of file node.cpp.