17 #ifndef CARTOGRAPHER_ROS_OCCUPANCY_GRID_H_ 18 #define CARTOGRAPHER_ROS_OCCUPANCY_GRID_H_ 23 #include "Eigen/Geometry" 25 #include "cartographer/mapping_2d/map_limits.h" 26 #include "cartographer/mapping_2d/proto/submaps_options.pb.h" 27 #include "nav_msgs/OccupancyGrid.h" 32 const std::vector<::cartographer::mapping::TrajectoryNode>&
34 const string& map_frame,
35 const ::cartographer::mapping_2d::proto::SubmapsOptions& submaps_options,
36 ::nav_msgs::OccupancyGrid*
const occupancy_grid);
42 const std::vector<::cartographer::mapping::TrajectoryNode>&
47 #endif // CARTOGRAPHER_ROS_OCCUPANCY_GRID_H_
void BuildOccupancyGrid2D(const std::vector<::cartographer::mapping::TrajectoryNode > &trajectory_nodes, const string &map_frame, const ::cartographer::mapping_2d::proto::SubmapsOptions &submaps_options,::nav_msgs::OccupancyGrid *const occupancy_grid)
::cartographer::mapping_2d::MapLimits ComputeMapLimits(const double resolution, const std::vector<::cartographer::mapping::TrajectoryNode > &trajectory_nodes)