|
template<typename NumericType > |
void | nav_grid_pub_sub::fromOccupancyGrid (const nav_msgs::OccupancyGrid &msg, nav_grid::NavGrid< NumericType > &grid, const std::vector< NumericType > &cost_interpretation_table) |
| generic OccupancyGrid to NavGrid conversion using cost_interpretation_table More...
|
|
template<typename NumericType > |
nav_core2::UIntBounds | nav_grid_pub_sub::fromOccupancyGridUpdate (const map_msgs::OccupancyGridUpdate &update, nav_grid::NavGrid< NumericType > &grid, const std::vector< NumericType > &cost_interpretation_table) |
| generic OccupancyGridUpdate to NavGrid conversion using cost_interpretation_table. More...
|
|
template<typename NumericType > |
void | nav_grid_pub_sub::getExtremeValues (const nav_grid::NavGrid< NumericType > &grid, const NumericType unknown_value, NumericType &min_val, NumericType &max_val) |
| Retrieve the minimum and maximum values from a grid, ignoring the unknown_value. More...
|
|
nav_msgs::OccupancyGrid | nav_grid_pub_sub::toOccupancyGrid (const nav_grid::NavGrid< unsigned char > &grid, const ros::Time &stamp=ros::Time(0), const std::vector< unsigned char > cost_interpretation_table=std::vector< unsigned char >()) |
| NavGrid<unsigned char> to OccupancyGrid using cost_interpretation_table. More...
|
|
template<typename NumericType > |
nav_msgs::OccupancyGrid | nav_grid_pub_sub::toOccupancyGrid (const nav_grid::NavGrid< NumericType > &grid, const NumericType min_value, const NumericType max_value, const NumericType unknown_value, const ros::Time &stamp=ros::Time(0)) |
| generic NavGrid to OccupancyGrid using scaling. Min and max explicitly provided. More...
|
|
template<typename NumericType > |
nav_msgs::OccupancyGrid | nav_grid_pub_sub::toOccupancyGrid (const nav_grid::NavGrid< NumericType > &grid, const NumericType unknown_value=std::numeric_limits< NumericType >::max(), const ros::Time &stamp=ros::Time(0)) |
| generic NavGrid to OccupancyGrid using scaling. Min and max not provided, so they are determined first. More...
|
|
map_msgs::OccupancyGridUpdate | nav_grid_pub_sub::toOccupancyGridUpdate (const nav_grid::NavGrid< unsigned char > &grid, const nav_core2::UIntBounds &bounds, const ros::Time &stamp=ros::Time(0), const std::vector< unsigned char > cost_interpretation_table=std::vector< unsigned char >()) |
| NavGrid<unsigned char> to OccupancyGridUpdate using cost_interpretation_table. More...
|
|
template<typename NumericType > |
map_msgs::OccupancyGridUpdate | nav_grid_pub_sub::toOccupancyGridUpdate (const nav_grid::NavGrid< NumericType > &grid, const nav_core2::UIntBounds &bounds, const NumericType min_value, const NumericType max_value, const NumericType unknown_value, const ros::Time &stamp=ros::Time(0)) |
| generic NavGrid to OccupancyGridUpdate using scaling. Min and max explicitly provided. More...
|
|