#include <MapHelper.hpp>
|
bool | doRaytracing (const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint) |
|
bool | doRaytracing (const SimpleVector3 &fromPoint, const SimpleVector3 &toPoint, Ray &ray) |
|
int8_t | getCollisionThreshold () |
|
int8_t | getCostmapOccupancyValue (const SimpleVector3 &position) |
|
int8_t | getCostmapOccupancyValue (const int32_t &mapX, const int32_t &mapY) |
|
int8_t | getMapOccupancyValue (const SimpleVector3 &position) |
|
int8_t | getMapOccupancyValue (const int32_t &mapX, const int32_t &mapY) |
|
float | getMetricHeight () |
|
float | getMetricWidth () |
|
SimpleQuaternion | getOrientation () |
|
int8_t | getRaytracingMapOccupancyValue (const SimpleVector3 &position) |
|
int8_t | getRaytracingMapOccupancyValue (const int32_t &mapX, const int32_t &mapY) |
|
float | getSquaredDistance (const SimpleVector3 &start, const SimpleVector3 &goal) |
|
SimpleVector3 | getTranslation () |
|
bool | isOccupancyValueAcceptable (const int8_t &occupancyValue) |
|
| MapHelper (const std::string &mapTopicName="map", const std::string &getPlanServiceName="move_base/make_plan") |
|
void | mapToWorldCoordinates (const int32_t &x, const int32_t &y, SimpleVector3 &result) |
|
void | mapToWorldCoordinates (const SimpleVector3 &position, SimpleVector3 &result) |
|
void | mapToWorldSize (const double &size, double &result) |
|
void | setCollisionThreshold (int8_t thresholdValue) |
|
void | worldToMapCoordinates (const SimpleVector3 &position, int32_t &x, int32_t &y) |
|
void | worldToMapCoordinates (const SimpleVector3 &position, SimpleVector3 &result) |
|
void | worldToMapSize (const double &size, double &result) |
|
virtual | ~MapHelper () |
|
Definition at line 65 of file MapHelper.hpp.
next_best_view::MapHelper::MapHelper |
( |
const std::string & |
mapTopicName = "map" , |
|
|
const std::string & |
getPlanServiceName = "move_base/make_plan" |
|
) |
| |
|
inline |
We must wait for the map is published on the map server, to use the right map of the navigation.
Definition at line 79 of file MapHelper.hpp.
virtual next_best_view::MapHelper::~MapHelper |
( |
| ) |
|
|
inlinevirtual |
void next_best_view::MapHelper::aggregateRaytracingMap |
( |
| ) |
|
|
inlineprivate |
int8_t next_best_view::MapHelper::getCollisionThreshold |
( |
| ) |
|
|
inline |
int8_t next_best_view::MapHelper::getCostmapOccupancyValue |
( |
const SimpleVector3 & |
position | ) |
|
|
inline |
int8_t next_best_view::MapHelper::getCostmapOccupancyValue |
( |
const int32_t & |
mapX, |
|
|
const int32_t & |
mapY |
|
) |
| |
|
inline |
int8_t next_best_view::MapHelper::getMapOccupancyValue |
( |
const SimpleVector3 & |
position | ) |
|
|
inline |
int8_t next_best_view::MapHelper::getMapOccupancyValue |
( |
const int32_t & |
mapX, |
|
|
const int32_t & |
mapY |
|
) |
| |
|
inline |
float next_best_view::MapHelper::getMetricHeight |
( |
| ) |
|
|
inline |
float next_best_view::MapHelper::getMetricWidth |
( |
| ) |
|
|
inline |
int8_t next_best_view::MapHelper::getOccupancyValue |
( |
const nav_msgs::OccupancyGrid & |
map, |
|
|
const SimpleVector3 & |
position |
|
) |
| |
|
inlineprivate |
int8_t next_best_view::MapHelper::getOccupancyValue |
( |
const costmap_2d::Costmap2D & |
costmap, |
|
|
const SimpleVector3 & |
position |
|
) |
| |
|
inlineprivate |
int8_t next_best_view::MapHelper::getOccupancyValue |
( |
const nav_msgs::OccupancyGrid & |
map, |
|
|
const int32_t & |
mapX, |
|
|
const int32_t & |
mapY |
|
) |
| |
|
inlineprivate |
int8_t next_best_view::MapHelper::getOccupancyValue |
( |
const costmap_2d::Costmap2D & |
costmap, |
|
|
const int32_t & |
mapX, |
|
|
const int32_t & |
mapY |
|
) |
| |
|
inlineprivate |
int8_t next_best_view::MapHelper::getRaytracingMapOccupancyValue |
( |
const SimpleVector3 & |
position | ) |
|
|
inline |
int8_t next_best_view::MapHelper::getRaytracingMapOccupancyValue |
( |
const int32_t & |
mapX, |
|
|
const int32_t & |
mapY |
|
) |
| |
|
inline |
bool next_best_view::MapHelper::isOccupancyValueAcceptable |
( |
const int8_t & |
occupancyValue | ) |
|
|
inline |
void next_best_view::MapHelper::mapReceived |
( |
nav_msgs::OccupancyGrid |
map | ) |
|
|
inlineprivate |
void next_best_view::MapHelper::mapToWorldCoordinates |
( |
const int32_t & |
x, |
|
|
const int32_t & |
y, |
|
|
SimpleVector3 & |
result |
|
) |
| |
|
inline |
void next_best_view::MapHelper::mapToWorldSize |
( |
const double & |
size, |
|
|
double & |
result |
|
) |
| |
|
inline |
void next_best_view::MapHelper::setCollisionThreshold |
( |
int8_t |
thresholdValue | ) |
|
|
inline |
void next_best_view::MapHelper::setCostmap |
( |
| ) |
|
|
inlineprivate |
void next_best_view::MapHelper::worldToMapCoordinates |
( |
const SimpleVector3 & |
position, |
|
|
int32_t & |
x, |
|
|
int32_t & |
y |
|
) |
| |
|
inline |
void next_best_view::MapHelper::worldToMapSize |
( |
const double & |
size, |
|
|
double & |
result |
|
) |
| |
|
inline |
int8_t next_best_view::MapHelper::mCollisionThreshold |
|
private |
costmap_2d::Costmap2D next_best_view::MapHelper::mCostmap |
|
private |
int8_t next_best_view::MapHelper::mCostTranslationTable[256] |
|
private |
nav_msgs::OccupancyGrid next_best_view::MapHelper::mMap |
|
private |
bool next_best_view::MapHelper::mMapReceived |
|
private |
nav_msgs::OccupancyGrid next_best_view::MapHelper::mRaytracingMap |
|
private |
The documentation for this class was generated from the following file:
asr_next_best_view
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Thu Jan 9 2020 07:20:18