|
| using | OOPE = MaxOccupancyObservationPE |
| |
| using | SPE = typename ScanMatcherTestBase< MapType >::DefaultSPE |
| |
| using | SPW = EvenSPW |
| |
| using | DefaultSPE = WeightedMeanPointProbabilitySPE |
| |
| | BFMRScanMatcherTestBase () |
| |
| RobotPoseDelta | default_acceptable_error () override |
| |
| void | init_pose_facing_top_cecum_bound () |
| |
| GridScanMatcher & | scan_matcher () override |
| |
| virtual void | add_primitive_to_map (const TextRasterMapPrimitive &mp, const DiscretePoint2D &offset, int w_scale, int h_scale) |
| |
| virtual bool | is_result_noise_acceptable (const TransformedLaserScan &raw_scan, const RobotPoseDelta &init_noise, const RobotPoseDelta &noise) |
| |
| | ScanMatcherTestBase (std::shared_ptr< ScanProbabilityEstimator > prob_est, int map_w, int map_h, double map_scale, const LaserScannerParams &dflt_lsp) |
| |
| void | test_scan_matcher (const LaserScannerParams &lsp, const RobotPoseDelta &noise, const RobotPoseDelta &acc_error) |
| |
| void | test_scan_matcher (const RobotPoseDelta &noise, const RobotPoseDelta &acc_error) |
| |
| void | test_scan_matcher (const RobotPoseDelta &noise) |
| |
| | bfmrsm |
| |
| BruteForceMultiResolutionScanMatcher | bfmrsm |
| |
| | Cecum_Patch_H |
| |
| LaserScannerParams | default_lsp |
| |
| MapType | map |
| |
| RobotPose | rpose |
| |
| std::shared_ptr< ScanProbabilityEstimator > | spe |
| |
| static constexpr int | LS_FoW |
| |
| static constexpr double | LS_Max_Dist |
| |
| static constexpr int | LS_Pts_Nm |
| |
| static constexpr int | Map_Height |
| |
| static constexpr double | Map_Scale |
| |
| static constexpr int | Map_Width |
| |
| static constexpr int | Patch_Scale |
| |
| static constexpr double | SM_Ang_Step |
| |
| static constexpr double | SM_Max_Rotation_Error |
| |
| static constexpr double | SM_Max_Translation_Error |
| |
| static constexpr double | SM_Transl_Step |
| |
| static constexpr RobotPoseDelta | Acceptable_Error |
| |
template<typename MapType>
class BFMRScanMatcherSmokeTest< MapType >
Definition at line 84 of file bf_multi_res_sm_smoke_test.cpp.