#include <sequential_scan_matcher.h>

Public Member Functions | |
| void | addRunningNode (const pg::NodeId &n) |
| ChainVec | candidateChains (const pg::PoseGraph &graph, pose_graph::NodeId ref_node, const geometry_msgs::Point &barycenter, const LaserPtr scan) const |
| NodeConstraintVector | getConstraints (const pg::PoseGraph &g, const pose_graph::NodeId ref_node, const Pose &initial_pose_estimate, const LaserPtr scan) const |
| SequentialScanMatcher (const geometry_msgs::Pose2D &laser_offset, double max_link_length, unsigned min_chain_length, double min_response, bool use_covariances) | |
Private Attributes | |
| KartoMatcherPtr | matcher_ |
| const double | max_link_length_ |
| const double | min_chain_length_ |
| const double | min_response_ |
| boost::circular_buffer < pg::NodeId > | running_nodes_ |
| const double | use_covariances_ |
Definition at line 51 of file sequential_scan_matcher.h.
| graph_slam::SequentialScanMatcher::SequentialScanMatcher | ( | const geometry_msgs::Pose2D & | laser_offset, |
| double | max_link_length, | ||
| unsigned | min_chain_length, | ||
| double | min_response, | ||
| bool | use_covariances | ||
| ) |
Definition at line 47 of file sequential_scan_matcher.cpp.
| void graph_slam::SequentialScanMatcher::addRunningNode | ( | const pg::NodeId & | n | ) |
Definition at line 151 of file sequential_scan_matcher.cpp.
| ChainVec graph_slam::SequentialScanMatcher::candidateChains | ( | const pg::PoseGraph & | graph, |
| pose_graph::NodeId | ref_node, | ||
| const geometry_msgs::Point & | barycenter, | ||
| const LaserPtr | scan | ||
| ) | const |
Definition at line 126 of file sequential_scan_matcher.cpp.
| NodeConstraintVector graph_slam::SequentialScanMatcher::getConstraints | ( | const pg::PoseGraph & | g, |
| const pose_graph::NodeId | ref_node, | ||
| const Pose & | initial_pose_estimate, | ||
| const LaserPtr | scan | ||
| ) | const |
Definition at line 73 of file sequential_scan_matcher.cpp.
KartoMatcherPtr graph_slam::SequentialScanMatcher::matcher_ [mutable, private] |
Definition at line 70 of file sequential_scan_matcher.h.
const double graph_slam::SequentialScanMatcher::max_link_length_ [private] |
Definition at line 72 of file sequential_scan_matcher.h.
const double graph_slam::SequentialScanMatcher::min_chain_length_ [private] |
Definition at line 73 of file sequential_scan_matcher.h.
const double graph_slam::SequentialScanMatcher::min_response_ [private] |
Definition at line 74 of file sequential_scan_matcher.h.
boost::circular_buffer<pg::NodeId> graph_slam::SequentialScanMatcher::running_nodes_ [private] |
Definition at line 77 of file sequential_scan_matcher.h.
const double graph_slam::SequentialScanMatcher::use_covariances_ [private] |
Definition at line 75 of file sequential_scan_matcher.h.