#include <brute_force_scan_matcher.h>
|
| BruteForceScanMatcher (std::shared_ptr< ScanProbabilityEstimator > estimator, double from_x, double to_x, double step_x, double from_y, double to_y, double step_y, double from_t, double to_t, double step_t) |
|
auto | pose_enumerator () const |
|
| PoseEnumerationScanMatcher (std::shared_ptr< ScanProbabilityEstimator > spe, std::shared_ptr< PoseEnumerator > pe) |
|
double | process_scan (const TransformedLaserScan &raw_scan, const RobotPose &init_pose, const GridMap &map, RobotPoseDelta &pose_delta) override |
|
void | reset_state () override |
|
void | set_pose_enumerator (std::shared_ptr< PoseEnumerator > pe) |
|
LaserScan2D | filter_scan (const LaserScan2D &scan, const RobotPose &pose, const GridMap &map) |
|
| GridScanMatcher (SPE estimator, double max_x_error=0, double max_y_error=0, double max_th_error=0) |
|
double | scan_probability (const LaserScan2D &scan, const RobotPose &pose, const GridMap &map) const |
|
double | scan_probability (const LaserScan2D &scan, const RobotPose &pose, const GridMap &map, const SPEParams &p) const |
|
SPE | scan_probability_estimator () const |
|
void | set_lookup_ranges (double x, double y=0, double th=0) |
|
void | set_scan_probability_estimator (SPE spe) |
|
void | subscribe (std::shared_ptr< GridScanMatcherObserver > obs) |
|
void | unsubscribe (std::shared_ptr< GridScanMatcherObserver > obs) |
|
virtual | ~GridScanMatcher ()=default |
|
Definition at line 68 of file brute_force_scan_matcher.h.
BruteForceScanMatcher::BruteForceScanMatcher |
( |
std::shared_ptr< ScanProbabilityEstimator > |
estimator, |
|
|
double |
from_x, |
|
|
double |
to_x, |
|
|
double |
step_x, |
|
|
double |
from_y, |
|
|
double |
to_y, |
|
|
double |
step_y, |
|
|
double |
from_t, |
|
|
double |
to_t, |
|
|
double |
step_t |
|
) |
| |
|
inline |
The documentation for this class was generated from the following file: