17 #ifndef CARTOGRAPHER_MAPPING_2D_SPARSE_POSE_GRAPH_CONSTRAINT_BUILDER_H_ 18 #define CARTOGRAPHER_MAPPING_2D_SPARSE_POSE_GRAPH_CONSTRAINT_BUILDER_H_ 27 #include "Eigen/Geometry" 34 #include "cartographer/mapping/sparse_pose_graph/proto/constraint_builder_options.pb.h" 45 namespace mapping_2d {
46 namespace sparse_pose_graph {
63 using Result = std::vector<Constraint>;
66 const mapping::sparse_pose_graph::proto::ConstraintBuilderOptions&
115 std::unique_ptr<scan_matching::FastCorrelativeScanMatcher>
132 const mapping::SubmapId& submap_id)
EXCLUDES(mutex_);
141 const mapping::SubmapId& submap_id, const mapping::
Submap* submap,
142 const mapping::NodeId& node_id,
bool match_full_submap,
143 mapping::TrajectoryConnectivity* trajectory_connectivity,
145 const transform::
Rigid2d& initial_relative_pose,
152 const mapping::sparse_pose_graph::proto::ConstraintBuilderOptions
options_;
154 common::Mutex mutex_;
157 std::unique_ptr<std::function<
void(const
Result&)>> when_done_
163 int current_computation_
GUARDED_BY(mutex_) = 0;
167 std::map<
int,
int> pending_computations_
GUARDED_BY(mutex_);
179 std::map<mapping::SubmapId, std::vector<std::function<
void()>>>
187 common::Histogram score_histogram_
GUARDED_BY(mutex_);
194 #endif // CARTOGRAPHER_MAPPING_2D_SPARSE_POSE_GRAPH_CONSTRAINT_BUILDER_H_
int GetNumFinishedScans()
const ProbabilityGrid * probability_grid
void WhenDone(std::function< void(const Result &)> callback)
void DeleteScanMatcher(const mapping::SubmapId &submap_id)
void ConstructSubmapScanMatcher(const mapping::SubmapId &submap_id, const ProbabilityGrid *submap) EXCLUDES(mutex_)
std::unique_ptr< scan_matching::FastCorrelativeScanMatcher > fast_correlative_scan_matcher
void FinishComputation(int computation_index) EXCLUDES(mutex_)
transform::Rigid2d ComputeSubmapPose(const mapping::Submap &submap)
void ScheduleSubmapScanMatcherConstructionAndQueueWorkItem(const mapping::SubmapId &submap_id, const ProbabilityGrid *submap, std::function< void()> work_item) REQUIRES(mutex_)
std::vector< Constraint > Result
std::unique_ptr< std::function< void(const Result &)> > when_done_ GUARDED_BY(mutex_)
ConstraintBuilder & operator=(const ConstraintBuilder &)=delete
ConstraintBuilder(const mapping::sparse_pose_graph::proto::ConstraintBuilderOptions &options, common::ThreadPool *thread_pool)
void MaybeAddConstraint(const mapping::SubmapId &submap_id, const mapping::Submap *submap, const mapping::NodeId &node_id, const sensor::PointCloud *point_cloud, const transform::Rigid2d &initial_relative_pose)
const mapping::sparse_pose_graph::proto::ConstraintBuilderOptions options_
common::FixedRatioSampler sampler_
void MaybeAddGlobalConstraint(const mapping::SubmapId &submap_id, const mapping::Submap *submap, const mapping::NodeId &node_id, const sensor::PointCloud *point_cloud, mapping::TrajectoryConnectivity *trajectory_connectivity)
std::vector< Eigen::Vector3f > PointCloud
common::ThreadPool * thread_pool_
const sensor::AdaptiveVoxelFilter adaptive_voxel_filter_
scan_matching::CeresScanMatcher ceres_scan_matcher_
const SubmapScanMatcher * GetSubmapScanMatcher(const mapping::SubmapId &submap_id) EXCLUDES(mutex_)
void ComputeConstraint(const mapping::SubmapId &submap_id, const mapping::Submap *submap, const mapping::NodeId &node_id, bool match_full_submap, mapping::TrajectoryConnectivity *trajectory_connectivity, const sensor::PointCloud *point_cloud, const transform::Rigid2d &initial_relative_pose, std::unique_ptr< Constraint > *constraint) EXCLUDES(mutex_)