Parameters for map merging high-level interface. More...
#include <map_merging.h>
Static Public Member Functions | |
static MapMergingParams | fromCommandLine (int argc, char **argv) |
Sources parameters from command line arguments. More... | |
static MapMergingParams | fromROSNode (const ros::NodeHandle &node) |
Sources parameters from ROS node parameters. More... | |
Public Attributes | |
double | confidence_threshold = 0.0 |
double | descriptor_radius = resolution * 8.0 |
Descriptor | descriptor_type = Descriptor::PFH |
EstimationMethod | estimation_method = EstimationMethod::MATCHING |
double | inlier_threshold = resolution * 5.0 |
double | keypoint_threshold = 5.0 |
Keypoint | keypoint_type = Keypoint::SIFT |
size_t | matching_k = 5 |
double | max_correspondence_distance = inlier_threshold * 2.0 |
int | max_iterations = 500 |
double | normal_radius = resolution * 6.0 |
int | outliers_min_neighbours = 50 |
double | output_resolution = 0.05 |
bool | refine_transform = true |
double | resolution = 0.1 |
double | transform_epsilon = 1e-2 |
Parameters for map merging high-level interface.
Contains all tunables for estimating transformation between n maps and for compositing the global map
Definition at line 28 of file map_merging.h.
|
static |
Sources parameters from command line arguments.
Uses PCL's command line parser to initialize the parameters. Format is --param_name <value>
. param_name is the same as the struct member.
argc | arguments count |
argv | program arguments |
|
static |
Sources parameters from ROS node parameters.
Parameter names are the same as the struct member.
node | ROS node to source parameters from |
double map_merge_3d::MapMergingParams::confidence_threshold = 0.0 |
Definition at line 43 of file map_merging.h.
double map_merge_3d::MapMergingParams::descriptor_radius = resolution * 8.0 |
Definition at line 30 of file map_merging.h.
Descriptor map_merge_3d::MapMergingParams::descriptor_type = Descriptor::PFH |
Definition at line 35 of file map_merging.h.
EstimationMethod map_merge_3d::MapMergingParams::estimation_method = EstimationMethod::MATCHING |
Definition at line 36 of file map_merging.h.
double map_merge_3d::MapMergingParams::inlier_threshold = resolution * 5.0 |
Definition at line 38 of file map_merging.h.
double map_merge_3d::MapMergingParams::keypoint_threshold = 5.0 |
Definition at line 34 of file map_merging.h.
Keypoint map_merge_3d::MapMergingParams::keypoint_type = Keypoint::SIFT |
Definition at line 33 of file map_merging.h.
size_t map_merge_3d::MapMergingParams::matching_k = 5 |
Definition at line 41 of file map_merging.h.
double map_merge_3d::MapMergingParams::max_correspondence_distance = inlier_threshold * 2.0 |
Definition at line 39 of file map_merging.h.
int map_merge_3d::MapMergingParams::max_iterations = 500 |
Definition at line 40 of file map_merging.h.
double map_merge_3d::MapMergingParams::normal_radius = resolution * 6.0 |
Definition at line 32 of file map_merging.h.
int map_merge_3d::MapMergingParams::outliers_min_neighbours = 50 |
Definition at line 31 of file map_merging.h.
double map_merge_3d::MapMergingParams::output_resolution = 0.05 |
Definition at line 44 of file map_merging.h.
bool map_merge_3d::MapMergingParams::refine_transform = true |
Definition at line 37 of file map_merging.h.
double map_merge_3d::MapMergingParams::resolution = 0.1 |
Definition at line 29 of file map_merging.h.
double map_merge_3d::MapMergingParams::transform_epsilon = 1e-2 |
Definition at line 42 of file map_merging.h.