Go to the documentation of this file.
47 SLAMAlign::SLAMAlign(
const SLAMOptions&
options,
const vector<SLAMScanPtr>& scans, std::vector<bool> new_scans)
48 : m_options(
options), m_scans(scans), m_graph(&m_options), m_foundLoop(false), m_loopIndexCount(0), m_new_scans(new_scans)
51 for (
auto& scan : m_scans)
58 : m_options(
options), m_graph(&m_options), m_foundLoop(false), m_loopIndexCount(0), m_new_scans(new_scans)
100 size_t prev =
scan->numPoints();
114 if (
scan->numPoints() < prev)
120 cout <<
"Removed " << (prev -
scan->numPoints()) <<
" / " << prev <<
" Points -> " <<
scan->numPoints() <<
" left" << endl;
142 string scan_number_string = to_string(
m_scans.size() - 1);
149 cout <<
m_scans.size() << endl;
154 cout <<
"Iteration " << setw(scan_number_string.length()) <<
m_icp_graph.at(i).second <<
"/" << scan_number_string <<
": " << endl;
158 cout << setw(scan_number_string.length()) <<
m_icp_graph.at(i).second <<
"/" << scan_number_string <<
": " << flush;
232 cout <<
"check if a loop exists. current scan: " <<
m_icp_graph.at(last).second << endl;
234 int no_loop = INT_MAX;
235 vector<SLAMScanPtr> scans;
236 std::vector<bool> new_scans;
239 for (
int i = 0; i <= last; i++)
254 for (
int i = 0; i < scans.size(); i++)
256 double distance_to_other = sqrt(
257 pow(
m_scans.at(last)->innerScan()->poseEstimation(3,0) - scans.at(i)->innerScan()->poseEstimation(3,0), 2.0)+
258 pow(
m_scans.at(last)->innerScan()->poseEstimation(3,1) - scans.at(i)->innerScan()->poseEstimation(3,1), 2.0)+
259 pow(
m_scans.at(last)->innerScan()->poseEstimation(3,2) - scans.at(i)->innerScan()->poseEstimation(3,2), 2.0));
262 cout <<
"found loop" << endl;
276 bool hasLoop =
false;
279 vector<size_t> others;
314 cout <<
"Loopclose " <<
first <<
" -> " << last << endl;
318 for (
size_t i = 0; i < 3; i++)
336 for (
size_t i =
first + 3; i <= last - 3; i++)
338 double factor = (i -
first) / (
double)(last -
first);
340 Matrix4d delta = (
transform - Matrix4d::Identity()) * factor + Matrix4d::Identity();
348 for (
size_t i = 0; i < 3; i++)
353 for (
size_t i = 0; i <
first; i++)
357 for (
size_t i = last - 2; i <
m_scans.size(); i++)
389 cout <<
"create ICP Graph" << endl;
392 vector<vector<double>> mat(
m_scans.size());
397 for (
int i = 1; i <
m_scans.size(); i++)
406 vector<double> *v = &(mat.at(0));
407 auto trans_a =
m_scans.at(0)->innerScan()->poseEstimation.block<3, 1>(0, 3);
408 for (
int i = 0; i <
m_scans.size(); i++)
410 auto trans_b =
m_scans.at(i)->innerScan()->poseEstimation.block<3, 1>(0, 3);
412 double translation_diff = 0.0;
413 for(
int i = 0; i < 3; ++i)
415 translation_diff+= std::pow(trans_a[i] - trans_b[i], 2);
417 v->push_back(std::sqrt(translation_diff));
421 cout <<
"Calculated euclidean distancex: scan_0, scan_" << i <<
", d="<< v->at(i) << endl;
427 vector<bool> scan_in_graph(
m_scans.size());
428 scan_in_graph.at(0) =
true;
429 for (
int i = 1; i < scan_in_graph.size(); i++)
431 scan_in_graph.at(i) =
false;
434 for(
int i = 1; i <
m_scans.size(); i++)
436 double minimum = DBL_MAX;
441 for(
int x = 0; x < mat.size(); ++x)
443 for(
int y = 0 ; y < mat.at(x).size(); ++y)
445 if (!scan_in_graph.at(y) && x!=y && mat[x][y] < minimum)
455 m_icp_graph.push_back(std::pair<int, int>(old_scan,new_scan));
456 scan_in_graph.at(new_scan) =
true;
459 vector<double> *v = &(mat.at(new_scan));
460 auto trans_a =
m_scans.at(new_scan)->innerScan()->poseEstimation.block<3, 1>(0, 3);
461 for (
int i = 0; i <
m_scans.size(); i++)
463 auto trans_b =
m_scans.at(i)->innerScan()->poseEstimation.block<3, 1>(0, 3);
465 double translation_diff = 0.0;
466 for(
int i = 0; i < 3; ++i)
468 translation_diff+= std::pow(trans_a[i] - trans_b[i], 2);
470 v->push_back(std::sqrt(translation_diff));
474 cout <<
"Calculated euclidean distancex: scan_" << new_scan <<
", scan_" << i <<
", d="<< v->at(i) << endl;
482 cout <<
"create ICP Graph finish" << endl;
double reduction
The Voxel size for Octree based reduction.
void setMaxLeafSize(int maxLeafSize)
std::vector< SLAMScanPtr > m_scans
bool createFrames
Keep track of all previous Transformations of Scans for Animation purposes like 'show' from slam6D.
void reduceScan(const SLAMScanPtr &scan)
Applies all reductions to the Scan.
bool trustPose
Use the unmodified Pose of new Scans. If false, apply the relative refinement of previous Scans.
double icpMaxDistance
The maximum distance between two points during ICP.
@ UNUSED
The Scan did not change since the last Frame.
void applyTransform(SLAMScanPtr scan, const Matrix4d &transform)
Applies the Transformation to the specified Scan and adds a frame to all other Scans.
bool doLoopClosing
Use simple Loopclosing.
void setVerbose(bool verbose)
std::vector< bool > m_new_scans
void setEpsilon(double epsilon)
@ INVALID
The Scan has not been registered yet.
double epsilon
The epsilon difference between ICP-errors for the stop criterion of ICP.
const kaboom::Options * options
void doGraphSLAM(const std::vector< SLAMScanPtr > &scans, size_t last, const std::vector< bool > &new_scans=std::vector< bool >()) const
runs the GraphSLAM algorithm
bool useScanOrder
use scan order as icp order (if false: start with lowest distance)
SLAMScanPtr scan(size_t index) const
Returns a shared_ptr to a Scan.
bool verbose
Show more detailed output. Useful for fine-tuning Parameters or debugging.
Eigen::Matrix4d Matrix4d
Eigen 4x4 matrix, double precision.
void setOptions(const SLAMOptions &options)
Sets the SLAMOptions struct to the parameter.
SLAMOptions & options()
Returns a reference to the internal SLAMOptions struct.
void loopClose(size_t first, size_t last)
Closes a simple Loop between first and last.
void checkLoopClose(size_t last)
Checks for and executes any loopcloses that occur.
std::shared_ptr< SLAMScanWrapper > SLAMScanPtr
double slamMaxDistance
The maximum distance between two points during SLAM.
A class to align two Scans with ICP.
void match()
Executes SLAM on all current Scans.
void checkLoopCloseOtherOrder(size_t last)
checkLoopClose(size_t last) if the m_icp_graph is in a spezial order
bool metascan
Match scans to the combined Pointcloud of all previous Scans instead of just the last Scan.
void graphSLAM(size_t last)
Executes GraphSLAM up to and including the specified last Scan.
void createIcpGraph()
Create m_icp_graph which defined the order of registrations.
void setMaxMatchDistance(double distance)
double minDistance
Ignore all Points closer than to the origin of a scan.
bool doGraphSLAM
Use complex Loopclosing with GraphSLAM.
SLAMAlign(const SLAMOptions &options, const std::vector< SLAMScanPtr > &scans, std::vector< bool > new_scans=std::vector< bool >())
Creates a new SLAMAlign instance with the given Options and Scans.
double maxDistance
Ignore all Points farther away than from the origin of a scan.
void setMaxIterations(int iterations)
int slamIterations
Number of ICP iterations during Loopclosing and number of GraphSLAM iterations.
double slamEpsilon
The epsilon difference of SLAM corrections for the stop criterion of SLAM.
void finish()
Indicates that no new Scans will be added.
Transformd match()
Executes the ICPAlign.
@ LOOPCLOSE
The Scan was part of a Loopclose Iteration.
A struct to configure SLAMAlign.
std::vector< std::pair< int, int > > m_icp_graph
void addScan(const SLAMScanPtr &scan, bool match=false)
Adds a new Scan to the SLAM instance.
bool findCloseScans(const std::vector< SLAMScanPtr > &scans, size_t scan, const SLAMOptions &options, std::vector< size_t > &output)
finds Scans that are "close" to a Scan as determined by a Loopclosing strategy
int maxLeafSize
The maximum number of Points in a Leaf of a KDTree.
std::shared_ptr< Scan > ScanPtr
Shared pointer to scans.
lvr2
Author(s): Thomas Wiemann
, Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:25