Pipeline for merging overlapping occupancy grids. More...
#include <merging_pipeline.h>
Public Member Functions | |
| nav_msgs::OccupancyGrid::Ptr | composeGrids () |
| bool | estimateTransforms (FeatureType feature=FeatureType::AKAZE, double confidence=1.0) |
| template<typename InputIt > | |
| void | feed (InputIt grids_begin, InputIt grids_end) |
| std::vector< geometry_msgs::Transform > | getTransforms () const |
| template<typename InputIt > | |
| bool | setTransforms (InputIt transforms_begin, InputIt transforms_end) |
Private Attributes | |
| std::vector< nav_msgs::OccupancyGrid::ConstPtr > | grids_ |
| std::vector< cv::Mat > | images_ |
| std::vector< cv::Mat > | transforms_ |
Pipeline for merging overlapping occupancy grids.
Pipeline works on internally stored grids.
Definition at line 55 of file merging_pipeline.h.
| nav_msgs::OccupancyGrid::Ptr combine_grids::MergingPipeline::composeGrids | ( | ) |
Definition at line 156 of file merging_pipeline.cpp.
| bool combine_grids::MergingPipeline::estimateTransforms | ( | FeatureType | feature = FeatureType::AKAZE, |
| double | confidence = 1.0 |
||
| ) |
Definition at line 50 of file merging_pipeline.cpp.
| void combine_grids::MergingPipeline::feed | ( | InputIt | grids_begin, |
| InputIt | grids_end | ||
| ) |
Definition at line 75 of file merging_pipeline.h.
| std::vector< geometry_msgs::Transform > combine_grids::MergingPipeline::getTransforms | ( | ) | const |
Definition at line 217 of file merging_pipeline.cpp.
| bool combine_grids::MergingPipeline::setTransforms | ( | InputIt | transforms_begin, |
| InputIt | transforms_end | ||
| ) |
Definition at line 101 of file merging_pipeline.h.
|
private |
Definition at line 69 of file merging_pipeline.h.
|
private |
Definition at line 70 of file merging_pipeline.h.
|
private |
Definition at line 71 of file merging_pipeline.h.