#include <boost/thread/lock_guard.hpp>#include <cmath>#include <cost_map_core/cost_map_core.hpp>#include <cost_map_msgs/CostMap.h>#include <ecl/console.hpp>#include <limits>#include <map>#include <sensor_msgs/Image.h>#include <sensor_msgs/image_encodings.h>#include <std_msgs/UInt8MultiArray.h>#include <stdexcept>#include <string>#include "../../include/cost_map_ros/converter.hpp"#include <grid_map_costmap_2d/grid_map_costmap_2d.hpp>
Go to the source code of this file.
Namespaces | |
| namespace | cost_map |
Functions | |
| bool | cost_map::addLayerFromROSImage (const sensor_msgs::Image &image, const std::string &layer_name, cost_map::CostMap &cost_map) |
| bool | cost_map::fromCostmap2DROS (costmap_2d::Costmap2DROS &ros_costmap, const std::string &layer_name, cost_map::CostMap &cost_map) |
| Converts a ROS costmap to a costmap object. | |
| bool | cost_map::fromCostmap2DROSAtRobotPose (costmap_2d::Costmap2DROS &ros_costmap, const cost_map::Length &geometry, const std::string &layer_name, cost_map::CostMap &cost_map) |
| Converts a ROS costmap around the robot to a costmap object. | |
| bool | cost_map::fromMessage (const cost_map_msgs::CostMap &message, cost_map::CostMap &cost_map) |
| void | cost_map::toGridMap (const cost_map::CostMap cost_map, grid_map::GridMap &grid_map) |
| Convert a cost map object into a grid map object. | |
| void | cost_map::toMessage (const cost_map::CostMap &cost_map, cost_map_msgs::CostMap &message) |
| void | cost_map::toOccupancyGrid (const cost_map::CostMap &cost_map, const std::string &layer, nav_msgs::OccupancyGrid &msg) |
Definition in file converter.cpp.