10 #ifndef CLOOPCLOSERERD_H 11 #define CLOOPCLOSERERD_H 48 #include <Eigen/Dense> 242 template <
class GRAPH_T =
typename mrpt::graphs::CNetworkOfPoses2DInf>
255 typedef typename GRAPH_T::constraint_t::type_value
pose_t;
267 typedef std::map<std::pair<hypot_t*, hypot_t*>,
double>
286 const std::map<std::string, bool>& events_occurred);
287 void getEdgesStats(std::map<std::string, int>* edge_types_to_num)
const;
329 using namespace mrpt;
345 o <<
params.getAsString() << endl;
354 typedef std::map<mrpt::utils::TNodeID, node_props_t>
group_t;
397 const paths_t* groupA_opt_paths = NULL,
398 const paths_t* groupB_opt_paths = NULL);
428 const std::map<mrpt::utils::TNodeID, node_props_t>& group_params,
451 void loadFromConfigFile(
498 void loadFromConfigFile(
574 std::set<mrpt::utils::TNodeID>* nodes_set);
593 bool full_update =
false,
bool is_first_time_node_reg =
false);
617 std::pair<double, double>* centroid_coords)
const;
643 bool use_power_method =
false);
723 const hypotsp_t& vec_hypots,
const size_t&
id,
bool throw_exc =
true);
771 std::set<path_t*>* pool_of_paths)
const;
781 std::set<path_t*>* pool_of_paths,
const path_t& curr_path,
782 const std::set<mrpt::utils::TNodeID>& neibors)
const;
815 int max_nodes_in_group = 5);
Struct for storing together the parameters needed for ICP matching, laser scans visualization etc...
int m_text_index_curr_node_covariance
void toggleMapPartitionsVisualization()
Toggle the map partitions visualization objects.
partitions_t m_curr_partitions
Current partitions vector.
mrpt::slam::CIncrementalMapPartitioner m_partitioner
Instance responsible for partitioning the map.
bool mahalanobisDistanceOdometryToICPEdge(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, const constraint_t &rel_edge)
brief Compare the suggested ICP edge against the initial node difference.
parent_t::nodes_to_scans2D_t nodes_to_scans2D_t
friend std::ostream & operator<<(std::ostream &o, const self_t ¶ms)
Holds the data of an information path.
void loadParams(const std::string &source_fname)
const mrpt::utils::TColor m_curr_node_covariance_color
bool getPropsOfNodeID(const mrpt::utils::TNodeID &nodeID, global_pose_t *pose, mrpt::obs::CObservation2DRangeScan::Ptr &scan, const node_props_t *node_props=NULL) const
Fill the pose and LaserScan for the given nodeID.
const mrpt::utils::TColor laser_scans_color
see Constructor for initialization
static const path_t * findPathByEnds(const paths_t &vec_paths, const mrpt::utils::TNodeID &src, const mrpt::utils::TNodeID &dst, bool throw_exc=true)
Given a vector of TUncertaintyPath objects, find the one that has the given source and destination no...
mrpt::obs::CObservation2DRangeScan::Ptr m_first_laser_scan
Keep track of the first recorded laser scan so that it can be assigned to the root node when the NRD ...
int text_index_map_partitions
std::vector< uint32_t > vector_uint
void initMapPartitionsVisualization()
Initialize the visualization of the map partition objects.
mrpt::graphs::detail::THypothesis< GRAPH_T > hypot_t
void computeCentroidOfNodesVector(const vector_uint &nodes_list, std::pair< double, double > *centroid_coords) const
Compute the Centroid of a group of a vector of node positions.
TGetICPEdgeAdParams self_t
void updateCurrCovarianceVisualization()
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
bool m_partitions_full_update
Indicate whether the partitions have been updated recently.
virtual bool updateState(mrpt::obs::CActionCollection::Ptr action, mrpt::obs::CSensoryFrame::Ptr observations, mrpt::obs::CObservation::Ptr observation)
void setDijkstraExecutionThresh(size_t new_thresh)
void getDescriptiveReport(std::string *report_str) const
void getAsString(std::string *str) const
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
std::string keystroke_laser_scans
bool use_scan_matching
Indicate whethet to use scan-matching at all during graphSLAM [on by default].
const Scalar * const_iterator
pose_t init_estim
Initial ICP estimation.
TSlidingWindow mahal_distance_ICP_odom_win
Keep track of the mahalanobis distance between the initial pose difference and the suggested new edge...
Edge Registration Decider Interface from which RangeScanner-based ERDs can inherit from...
std::shared_ptr< CObservation2DRangeScan > Ptr
static hypot_t * findHypotByID(const hypotsp_t &vec_hypots, const size_t &id, bool throw_exc=true)
Given a vector of THypothesis objects, find the one that has the given ID.
std::vector< hypot_t > hypots_t
GRAPH_T::edges_map_t::const_iterator edges_citerator
virtual bool getICPEdge(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, constraint_t *rel_edge, mrpt::slam::CICP::TReturnInfo *icp_info=NULL, const TGetICPEdgeAdParams *ad_params=NULL)
Get the ICP Edge between the provided nodes.
virtual ~CLoopCloserERD()
node_props_t from_params
Ad.
Struct for passing additional parameters to the getICPEdge call.
std::map< std::pair< hypot_t *, hypot_t * >, double > hypotsp_to_consist_t
void addToPaths(std::set< path_t *> *pool_of_paths, const path_t &curr_path, const std::set< mrpt::utils::TNodeID > &neibors) const
Append the paths starting from the current node.
void registerHypothesis(const hypot_t &h)
Wrapper around the registerNewEdge method which accepts a THypothesis object instead.
void getAsString(std::string *str) const
void evaluatePartitionsForLC(const partitions_t &partitions)
Evaluate the given partitions for loop closures.
TLoopClosureParams m_lc_params
This class allows loading and storing values and vectors of different types from a configuration text...
bool m_visualize_curr_node_covariance
bool visualize_laser_scans
double LC_eigenvalues_ratio_thresh
Eigenvalues ratio for accepting/rejecting a hypothesis set.
std::map< mrpt::utils::TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > nodes_to_scans2D_t
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
uint64_t TNodeID
The type for node IDs in graphs of different types.
mrpt::graphslam::detail::TNodeProps< GRAPH_T > node_props_t
virtual void addScanMatchingEdges(const mrpt::utils::TNodeID &curr_nodeID)
Addd ICP constraints from X previous nodeIDs up to the given nodeID.
const mrpt::utils::TColor balloon_curr_color
std::string keystroke_map_partitions
std::map< int, vector_uint > m_partitionID_to_prev_nodes_list
Keep track of the evaluated partitions so they are not checked again if nothing changed in them...
TLaserParams m_laser_params
virtual void fetchNodeIDsForScanMatching(const mrpt::utils::TNodeID &curr_nodeID, std::set< mrpt::utils::TNodeID > *nodes_set)
Fetch a list of nodes with regards prior to the given nodeID for which to try and add scan matching e...
const mrpt::utils::TColor connecting_lines_color
CLoopCloserERD< GRAPH_T > decider_t
self type - Handy typedef
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
const partitions_t & getCurrPartitions() const
std::shared_ptr< CSensoryFrame > Ptr
int prev_nodes_for_ICP
How many nodes back to check ICP against?
bool m_is_first_time_node_reg
Track the first node registration occurance.
std::map< std::string, int > m_edge_types_to_nums
Keep track of the registered edge types.
std::shared_ptr< CObservation > Ptr
int full_partition_per_nodes
Full partition of map only afer X new nodes have been registered.
std::vector< path_t > paths_t
GLsizei const GLchar ** string
const double balloon_radius
bool computeDominantEigenVector(const mrpt::math::CMatrixDouble &consist_matrix, mrpt::math::dynamic_vector< double > *eigvec, bool use_power_method=false)
void setWindowManagerPtr(mrpt::graphslam::CWindowManager *win_manager)
GRAPH_T::global_pose_t global_pose_t
Class for keeping together all the RangeScanner-related functions.
mrpt::obs::CObservation2DRangeScan::Ptr m_last_laser_scan2D
Keep the last laser scan for visualization purposes.
void evalPWConsistenciesMatrix(const mrpt::math::CMatrixDouble &consist_matrix, const hypotsp_t &hypots_pool, hypotsp_t *valid_hypots)
Evalute the consistencies matrix, fill the valid hypotheses.
double generatePWConsistencyElement(const mrpt::utils::TNodeID &a1, const mrpt::utils::TNodeID &a2, const mrpt::utils::TNodeID &b1, const mrpt::utils::TNodeID &b2, const hypotsp_t &hypots, const paths_t *opt_paths=NULL)
Return the pair-wise consistency between the observations of the given nodes.
bool LC_check_curr_partition_only
flag indicating whether to check only the partition of the last registered node for potential loop cl...
std::vector< mrpt::vector_uint > partitions_t
Typedef for referring to a list of partitions.
parent_t::range_ops_t range_ops_t
void setLastLaserScan2D(mrpt::obs::CObservation2DRangeScan::Ptr scan)
Assign the last recorded 2D Laser scan.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
This class can be used to make partitions on a map/graph build from observations taken at some poses/...
std::shared_ptr< CActionCollection > Ptr
std::string getAsString() const
size_t getDijkstraExecutionThresh() const
Return the minimum number of nodes that should exist in the graph prior to running Dijkstra...
std::vector< hypot_t * > hypotsp_t
void registerNewEdge(const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, const constraint_t &rel_edge)
void splitPartitionToGroups(vector_uint &partition, vector_uint *groupA, vector_uint *groupB, int max_nodes_in_group=5)
Split an existing partition to Groups.
const double balloon_elevation
Class to monitor the evolution of a statistical quantity.
node_props_t to_params
Ad.
void updateLaserScansVisualization()
void checkPartitionsForLC(partitions_t *partitions_for_LC)
Check the registered so far partitions for potential loop closures.
Struct for passing additional parameters to the generateHypotsPool call.
The ICP algorithm return information.
void generatePWConsistenciesMatrix(const vector_uint &groupA, const vector_uint &groupB, const hypotsp_t &hypots_pool, mrpt::math::CMatrixDouble *consist_matrix, const paths_t *groupA_opt_paths=NULL, const paths_t *groupB_opt_paths=NULL)
Compute the pair-wise consistencies Matrix.
double m_lc_icp_constraint_factor
Factor used for accepting an ICP Constraint in the loop closure proc.
static hypot_t * findHypotByEnds(const hypotsp_t &vec_hypots, const mrpt::utils::TNodeID &from, const mrpt::utils::TNodeID &to, bool throw_exc=true)
Given a vector of THypothesis objects, find the one that has the given start and end nodes...
double m_offset_y_curr_node_covariance
GLsizei GLsizei GLchar * source
void toggleLaserScansVisualization()
togle the LaserScans visualization on and off
void updateMapPartitions(bool full_update=false, bool is_first_time_node_reg=false)
Split the currently registered graph nodes into partitions.
GRAPH_T::constraint_t::type_value pose_t
type of underlying poses (2D/3D).
int LC_min_remote_nodes
how many remote nodes (large nodID difference should there be before I consider the potential loop cl...
Edge Registration Decider scheme specialized in Loop Closing.
void getMinUncertaintyPath(const mrpt::utils::TNodeID from, const mrpt::utils::TNodeID to, path_t *path) const
Given two nodeIDs compute and return the path connecting them.
std::map< mrpt::utils::TNodeID, node_props_t > group_t
void generateHypotsPool(const vector_uint &groupA, const vector_uint &groupB, hypotsp_t *generated_hypots, const TGenerateHypotsPoolAdParams *ad_params=NULL)
Generate the hypothesis pool for all the inter-group constraints between two groups of nodes...
mrpt::graphslam::TUncertaintyPath< GRAPH_T > * popMinUncertaintyPath(std::set< path_t *> *pool_of_paths) const
Find the minimum uncertainty path from te given pool of TUncertaintyPath instances.
void initCurrCovarianceVisualization()
void execDijkstraProjection(mrpt::utils::TNodeID starting_node=0, mrpt::utils::TNodeID ending_node=INVALID_NODEID)
compute the minimum uncertainty of each node position with regards to the graph root.
void updateMapPartitionsVisualization()
Update the map partitions visualization.
void initLaserScansVisualization()
void notifyOfWindowEvents(const std::map< std::string, bool > &events_occurred)
size_t LC_min_nodeid_diff
nodeID difference for detecting potential loop closure in a partition.
An edge hypothesis between two nodeIDs.
const mrpt::utils::TColor balloon_std_color
double m_consec_icp_constraint_factor
Factor used for accepting an ICP Constraint as valid.
void dumpVisibilityErrorMsg(std::string viz_flag, int sleep_time=500)
mrpt::graphslam::TUncertaintyPath< GRAPH_T > path_t
CRangeScanEdgeRegistrationDecider< GRAPH_T > parent_t
Edge Registration Decider.
size_t m_dijkstra_node_count_thresh
Node Count lower bound before executing dijkstra.
double offset_y_map_partitions
GLenum const GLfloat * params
void getEdgesStats(std::map< std::string, int > *edge_types_to_num) const
Struct for storing together the loop-closing related parameters.
bool visualize_map_partitions
bool fillNodePropsFromGroupParams(const mrpt::utils::TNodeID &nodeID, const std::map< mrpt::utils::TNodeID, node_props_t > &group_params, node_props_t *node_props)
Fill the TNodeProps instance using the parameters from the map.
partitions_t m_last_partitions
Previous partitions vector.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
Class acts as a container for storing pointers to mrpt::gui::CDisplayWindow3D, mrpt::graphslam::CWind...
GRAPH_T::edges_map_t::iterator edges_iterator
std::map< mrpt::utils::TNodeID, path_t * > m_node_optimal_paths
Map that stores the lowest uncertainty path towards a node.
GRAPH_T::constraint_t constraint_t
Handy typedefs.
mrpt::graphslam::TUncertaintyPath< GRAPH_T > * queryOptimalPath(const mrpt::utils::TNodeID node) const
Query for the optimal path of a nodeID.
TSlidingWindow goodness_threshold_win
Keep track of ICP Goodness values for ICP between nearby nodes and adapt the Goodness threshold based...