occupied_space_cost_function_2d.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTION_2D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTION_2D_H_
00019 
00020 #include "cartographer/mapping/2d/grid_2d.h"
00021 #include "cartographer/sensor/point_cloud.h"
00022 #include "ceres/ceres.h"
00023 
00024 namespace cartographer {
00025 namespace mapping {
00026 namespace scan_matching {
00027 
00028 // Creates a cost function for matching the 'point_cloud' to the 'grid' with
00029 // a 'pose'. The cost increases with poorer correspondence of the grid and the
00030 // point observation (e.g. points falling into less occupied space).
00031 ceres::CostFunction* CreateOccupiedSpaceCostFunction2D(
00032     const double scaling_factor, const sensor::PointCloud& point_cloud,
00033     const Grid2D& grid);
00034 
00035 }  // namespace scan_matching
00036 }  // namespace mapping
00037 }  // namespace cartographer
00038 
00039 #endif  // CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTION_2D_H_


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35