Namespaces | Classes | Typedefs | Functions | Variables
cost_map Namespace Reference

Namespaces

 Inflate
 

Classes

class  CircleIterator
 
class  CostMap
 
class  Costmap2DROSServiceProvider
 Provide cost_map::fromROSCostMap2D() as a ros service. More...
 
class  CostMapIterator
 
class  Deflate
 
class  EllipseIterator
 
class  Inflate
 
class  InflationComputer
 
class  LineIterator
 
class  LoadImageBundle
 Helper for loading and publishing image bundles. More...
 
class  PolygonIterator
 
class  ROSInflationComputer
 
class  SaveImageBundle
 Helper for saving an image bundle from a cost map topic. More...
 
class  SpiralIterator
 
class  SubmapGeometry
 
class  SubmapIterator
 

Typedefs

typedef grid_map::BufferRegion BufferRegion
 
typedef std::shared_ptr< cost_map::CostMap const > CostMapConstPtr
 
typedef std::shared_ptr< cost_map::CostMapCostMapPtr
 
typedef grid_map::Matrix DataMatrix
 
typedef Matrix::Scalar DataType
 
typedef grid_map::Index Index
 
typedef grid_map::Length Length
 
typedef Eigen::Matrix< unsigned char, Eigen::Dynamic, Eigen::Dynamic > Matrix
 
typedef grid_map::Polygon Polygon
 
typedef grid_map::Position Position
 
typedef grid_map::Position3 Position3
 
typedef grid_map::Size Size
 
typedef grid_map::Time Time
 
typedef grid_map::Vector Vector
 
typedef grid_map::Vector3 Vector3
 

Functions

bool addLayerFromROSImage (const sensor_msgs::Image &image, const std::string &layer_name, cost_map::CostMap &cost_map)
 
bool fromCostmap2DROS (costmap_2d::Costmap2DROS &ros_costmap, const std::string &layer_name, cost_map::CostMap &cost_map)
 Converts a ROS costmap to a costmap object. More...
 
bool 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. More...
 
void fromImageBundle (const std::string &filename, cost_map::CostMap &cost_map)
 Initialises a adds a single layer from a yaml/image resource pair. More...
 
bool fromMessage (const cost_map_msgs::CostMap &message, cost_map::CostMap &cost_map)
 
std::string resolveResourceName (const std::string &resource_name)
 Use rospack to resolve a costmap given a ros package resource name. More...
 
void toGridMap (const cost_map::CostMap cost_map, grid_map::GridMap &grid_map)
 Convert a cost map object into a grid map object. More...
 
void toImageBundle (const std::string &filename, const cost_map::CostMap &cost_map)
 Dump a cost map to an image bundle set of files. More...
 
void toMessage (const cost_map::CostMap &cost_map, cost_map_msgs::CostMap &message)
 
void toOccupancyGrid (const cost_map::CostMap &cost_map, const std::string &layer, nav_msgs::OccupancyGrid &msg)
 

Variables

const unsigned char FREE_SPACE
 
const unsigned char INSCRIBED_OBSTACLE
 
const unsigned char LETHAL_OBSTACLE
 
const unsigned char NO_INFORMATION
 

Function Documentation

bool cost_map::addLayerFromROSImage ( const sensor_msgs::Image &  image,
const std::string &  layer_name,
cost_map::CostMap cost_map 
)

Definition at line 37 of file converter.cpp.

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.

This copies the complete costmap and all relevant details of the underlying Costmap2D object. Note that it does not transfer properties in the Costmap2DROS object such as the notion of the robot pose.

Parameters
[in]ros_costmap: a traditional ros costmap object.
[in]layer_name: new costmaps have multiple layers, so important to specify a name
[out]costmap: a cost_map::CostMap object
Note
We should, but cannot use a const for the ros costmap since it hasn't been very well designed. Treat it as such and do not change the internals inside.

Definition at line 216 of file converter.cpp.

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.

This automatically affixes the cost map grid to the location of the robot in the ros costmap. Resolution is also carried across. The only configuration necessary is to specify how large the cost map should be. Take care that this subwindow does not go off the edge of the underlying ros costmap!

Parameters
[in]ros_costmap: a traditional ros costmap object (input).
[in]geometry: size of the subwindow (mxm)
[in]layer_name: new costmaps have multiple layers, so important to specify a name
[out]costmap: a cost_map::CostMap object
Note
We should, but cannot use a const for the ros costmap since it hasn't been very well designed. Treat it as such and do not change the internals inside.

Definition at line 229 of file converter.cpp.

void cost_map::fromImageBundle ( const std::string &  filename,
cost_map::CostMap cost_map 
)

Initialises a adds a single layer from a yaml/image resource pair.

Warning
this will change the geometry of the provided costmap and delete all layers!
Todo:
bool result/exception handling for when things go wrong
Parameters
[in]filename: yaml file
[out]cost_map:
Exceptions
std::logic_errorif the yaml couldn't be read, or the required yaml was not valid

Definition at line 34 of file image_bundles.cpp.

bool cost_map::fromMessage ( const cost_map_msgs::CostMap &  message,
cost_map::CostMap cost_map 
)

Converts a ROS cost map message to a cost map object.

Parameters
[in]messagethe cost map message.
[out]cost_mapthe cost map object to be initialized.
Returns
true if successful, false otherwise.

Definition at line 186 of file converter.cpp.

std::string cost_map::resolveResourceName ( const std::string &  resource_name)

Use rospack to resolve a costmap given a ros package resource name.

Costmaps are yaml files with configuration and a pointer to an opencv image to load. They are exported in the package.xml with a 'cost_map' tag and 'yaml' attribute.

http://wiki.ros.org/Names#Package_Resource_Names

Parameters
[in]resource_name: ros package resource name
Returns
absolute path to the resource
Exceptions
std::invalid_argumentif resource_name is the incorrect syntax
std::runtime_errorif the resource could not be found

Definition at line 23 of file utilities.cpp.

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.

Parameters
cost_map: incoming cost_map
grid_map: outgoing grid_map (Warning: this resets everything!)

Definition at line 130 of file converter.cpp.

void cost_map::toImageBundle ( const std::string &  filename,
const cost_map::CostMap cost_map 
)

Dump a cost map to an image bundle set of files.

This creates the specified yaml file with image bundle meta information and a set of png images alongside, one for each layer in the cost map.

Todo:
bool result/exception handling for when things go wrong
Parameters
[in]filename: name of the yaml file to write
[in]cost_map: cost map to dump

Definition at line 135 of file image_bundles.cpp.

void cost_map::toMessage ( const cost_map::CostMap cost_map,
cost_map_msgs::CostMap &  message 
)

Converts all layers of a grid map object to a ROS grid map message.

Parameters
[in]gridMapthe grid map object.
[out]messagethe grid map message to be populated.

Definition at line 154 of file converter.cpp.

void cost_map::toOccupancyGrid ( const cost_map::CostMap cost_map,
const std::string &  layer,
nav_msgs::OccupancyGrid &  msg 
)

Definition at line 245 of file converter.cpp.



cost_map_ros
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 13:03:48