A struct to configure SLAMAlign. More...
#include <SLAMOptions.hpp>
Public Attributes | |
double | closeLoopDistance = 500 |
int | closeLoopPairs = -1 |
bool | createFrames = false |
Keep track of all previous Transformations of Scans for Animation purposes like 'show' from slam6D. More... | |
double | diffAngle = 50 |
max difference of angle (sum of 3 angles) new and old More... | |
double | diffPosition = 50 |
max difference of position (euclidean distance) new and old More... | |
bool | doGraphSLAM = false |
Use complex Loopclosing with GraphSLAM. More... | |
bool | doLoopClosing = false |
Use simple Loopclosing. More... | |
double | epsilon = 0.00001 |
The epsilon difference between ICP-errors for the stop criterion of ICP. More... | |
int | icpIterations = 100 |
double | icpMaxDistance = 25 |
The maximum distance between two points during ICP. More... | |
int | loopSize = 20 |
double | maxDistance = -1 |
Ignore all Points farther away than from the origin of a scan. More... | |
int | maxLeafSize = 20 |
The maximum number of Points in a Leaf of a KDTree. More... | |
bool | metascan = false |
Match scans to the combined Pointcloud of all previous Scans instead of just the last Scan. More... | |
double | minDistance = -1 |
Ignore all Points closer than to the origin of a scan. More... | |
double | reduction = -1 |
The Voxel size for Octree based reduction. More... | |
double | rotate_angle = 0 |
rotate this angle around y axis More... | |
double | slamEpsilon = 0.5 |
The epsilon difference of SLAM corrections for the stop criterion of SLAM. More... | |
int | slamIterations = 50 |
Number of ICP iterations during Loopclosing and number of GraphSLAM iterations. More... | |
double | slamMaxDistance = 25 |
The maximum distance between two points during SLAM. More... | |
bool | trustPose = false |
Use the unmodified Pose of new Scans. If false, apply the relative refinement of previous Scans. More... | |
bool | useHDF = false |
Indicates if a HDF file containing the scans should be used. More... | |
bool | useScanOrder = true |
use scan order as icp order (if false: start with lowest distance) More... | |
bool | verbose = false |
Show more detailed output. Useful for fine-tuning Parameters or debugging. More... | |
A struct to configure SLAMAlign.
Definition at line 45 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::closeLoopDistance = 500 |
The maximum distance between two poses to consider a closed loop or an Edge in the GraphSLAM Graph. Mutually exclusive to closeLoopPairs
Definition at line 100 of file SLAMOptions.hpp.
int lvr2::SLAMOptions::closeLoopPairs = -1 |
The minimum pair overlap between two poses to consider a closed loop or an Edge in the GraphSLAM Graph. Mutually exclusive to closeLoopDistance
Definition at line 104 of file SLAMOptions.hpp.
bool lvr2::SLAMOptions::createFrames = false |
Keep track of all previous Transformations of Scans for Animation purposes like 'show' from slam6D.
Definition at line 56 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::diffAngle = 50 |
max difference of angle (sum of 3 angles) new and old
Definition at line 124 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::diffPosition = 50 |
max difference of position (euclidean distance) new and old
Definition at line 121 of file SLAMOptions.hpp.
bool lvr2::SLAMOptions::doGraphSLAM = false |
Use complex Loopclosing with GraphSLAM.
Definition at line 96 of file SLAMOptions.hpp.
bool lvr2::SLAMOptions::doLoopClosing = false |
Use simple Loopclosing.
Definition at line 93 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::epsilon = 0.00001 |
The epsilon difference between ICP-errors for the stop criterion of ICP.
Definition at line 88 of file SLAMOptions.hpp.
int lvr2::SLAMOptions::icpIterations = 100 |
Number of iterations for ICP. ICP should ideally converge before this number is met, but this number places an upper Bound on calculation time
Definition at line 79 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::icpMaxDistance = 25 |
The maximum distance between two points during ICP.
Definition at line 82 of file SLAMOptions.hpp.
int lvr2::SLAMOptions::loopSize = 20 |
The minimum number of Scans to be considered a Loop to prevent Loopclosing from triggering on adjacent Scans. Also used in GraphSLAM when considering other Scans for Edges. For Loopclosing, this value needs to be at least 6, for GraphSLAM at least 1
Definition at line 109 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::maxDistance = -1 |
Ignore all Points farther away than from the origin of a scan.
Definition at line 73 of file SLAMOptions.hpp.
int lvr2::SLAMOptions::maxLeafSize = 20 |
The maximum number of Points in a Leaf of a KDTree.
Definition at line 85 of file SLAMOptions.hpp.
bool lvr2::SLAMOptions::metascan = false |
Match scans to the combined Pointcloud of all previous Scans instead of just the last Scan.
Definition at line 53 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::minDistance = -1 |
Ignore all Points closer than to the origin of a scan.
Definition at line 70 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::reduction = -1 |
The Voxel size for Octree based reduction.
Definition at line 67 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::rotate_angle = 0 |
rotate this angle around y axis
Definition at line 130 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::slamEpsilon = 0.5 |
The epsilon difference of SLAM corrections for the stop criterion of SLAM.
Definition at line 118 of file SLAMOptions.hpp.
int lvr2::SLAMOptions::slamIterations = 50 |
Number of ICP iterations during Loopclosing and number of GraphSLAM iterations.
Definition at line 112 of file SLAMOptions.hpp.
double lvr2::SLAMOptions::slamMaxDistance = 25 |
The maximum distance between two points during SLAM.
Definition at line 115 of file SLAMOptions.hpp.
bool lvr2::SLAMOptions::trustPose = false |
Use the unmodified Pose of new Scans. If false, apply the relative refinement of previous Scans.
Definition at line 50 of file SLAMOptions.hpp.
bool lvr2::SLAMOptions::useHDF = false |
Indicates if a HDF file containing the scans should be used.
Definition at line 62 of file SLAMOptions.hpp.
bool lvr2::SLAMOptions::useScanOrder = true |
use scan order as icp order (if false: start with lowest distance)
Definition at line 127 of file SLAMOptions.hpp.
bool lvr2::SLAMOptions::verbose = false |
Show more detailed output. Useful for fine-tuning Parameters or debugging.
Definition at line 59 of file SLAMOptions.hpp.