Classes | Namespaces | Functions
converter.hpp File Reference
#include <grid_map_core/grid_map_core.hpp>
#include <grid_map_ros/grid_map_ros.hpp>
#include <grid_map_costmap_2d/grid_map_costmap_2d.hpp>
#include <cost_map_core/cost_map_core.hpp>
#include <cost_map_msgs/CostMap.h>
#include <cost_map_msgs/GetCostMap.h>
#include <costmap_2d/costmap_2d_ros.h>
#include <nav_msgs/OccupancyGrid.h>
#include <string>
Include dependency graph for converter.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  cost_map::Costmap2DROSServiceProvider
 Provide cost_map::fromROSCostMap2D() as a ros service. More...

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)


cost_map_ros
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 20:27:54