#include <scan_match_localization.h>

Public Member Functions | |
| LocalizationState | nextState (const LocalizationState &state, const Pose &fixed_frame_pose, const LaserPtr scan, const pose_graph::PoseGraph &graph, const NodePoseMap &optimized_poses) const |
| Compute the next state given the current state, odom pose, scan, graph, and optimized poses. | |
| ScanMatchLocalization (const geometry_msgs::Pose2D &laser_offset, double neighborhood_size, const unsigned localizations_per_scan_match) | |
| Constructor. | |
Private Attributes | |
| const unsigned | localizations_per_scan_match_ |
| KartoMatcherPtr | matcher_ |
| const double | max_link_length_ |
Definition at line 61 of file scan_match_localization.h.
| graph_slam::ScanMatchLocalization::ScanMatchLocalization | ( | const geometry_msgs::Pose2D & | laser_offset, |
| double | neighborhood_size, | ||
| const unsigned | localizations_per_scan_match | ||
| ) |
Constructor.
| laser_offset | Pose of laser in base frame |
| neighborhood_size | Size (m) of neighborhood of current node used for scan matching |
| localizations_per_scan_match | Do scan matching every so many localizations |
Definition at line 53 of file scan_match_localization.cpp.
| LocalizationState graph_slam::ScanMatchLocalization::nextState | ( | const LocalizationState & | state, |
| const Pose & | fixed_frame_pose, | ||
| const LaserPtr | scan, | ||
| const pose_graph::PoseGraph & | graph, | ||
| const NodePoseMap & | optimized_poses | ||
| ) | const |
Compute the next state given the current state, odom pose, scan, graph, and optimized poses.
Definition at line 59 of file scan_match_localization.cpp.
const unsigned graph_slam::ScanMatchLocalization::localizations_per_scan_match_ [private] |
Definition at line 85 of file scan_match_localization.h.
KartoMatcherPtr graph_slam::ScanMatchLocalization::matcher_ [mutable, private] |
Definition at line 83 of file scan_match_localization.h.
const double graph_slam::ScanMatchLocalization::max_link_length_ [private] |
Definition at line 80 of file scan_match_localization.h.