#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 63 of file MapHelper.hpp.
◆ MapHelper()
robot_model_services::MapHelper::MapHelper |
( |
const std::string & |
mapTopicName = "map" , |
|
|
const std::string & |
getPlanServiceName = "move_base/make_plan" |
|
) |
| |
|
inline |
◆ ~MapHelper()
virtual robot_model_services::MapHelper::~MapHelper |
( |
| ) |
|
|
inlinevirtual |
◆ aggregateRaytracingMap()
void robot_model_services::MapHelper::aggregateRaytracingMap |
( |
| ) |
|
|
inlineprivate |
◆ doRaytracing() [1/2]
◆ doRaytracing() [2/2]
◆ getCollisionThreshold()
int8_t robot_model_services::MapHelper::getCollisionThreshold |
( |
| ) |
|
|
inline |
◆ getCostmapOccupancyValue() [1/2]
int8_t robot_model_services::MapHelper::getCostmapOccupancyValue |
( |
const SimpleVector3 & |
position | ) |
|
|
inline |
◆ getCostmapOccupancyValue() [2/2]
int8_t robot_model_services::MapHelper::getCostmapOccupancyValue |
( |
const int32_t & |
mapX, |
|
|
const int32_t & |
mapY |
|
) |
| |
|
inline |
◆ getMapOccupancyValue() [1/2]
int8_t robot_model_services::MapHelper::getMapOccupancyValue |
( |
const SimpleVector3 & |
position | ) |
|
|
inline |
◆ getMapOccupancyValue() [2/2]
int8_t robot_model_services::MapHelper::getMapOccupancyValue |
( |
const int32_t & |
mapX, |
|
|
const int32_t & |
mapY |
|
) |
| |
|
inline |
◆ getMetricHeight()
float robot_model_services::MapHelper::getMetricHeight |
( |
| ) |
|
|
inline |
◆ getMetricWidth()
float robot_model_services::MapHelper::getMetricWidth |
( |
| ) |
|
|
inline |
◆ getOccupancyValue() [1/4]
int8_t robot_model_services::MapHelper::getOccupancyValue |
( |
const nav_msgs::OccupancyGrid & |
map, |
|
|
const SimpleVector3 & |
position |
|
) |
| |
|
inlineprivate |
◆ getOccupancyValue() [2/4]
◆ getOccupancyValue() [3/4]
int8_t robot_model_services::MapHelper::getOccupancyValue |
( |
const nav_msgs::OccupancyGrid & |
map, |
|
|
const int32_t & |
mapX, |
|
|
const int32_t & |
mapY |
|
) |
| |
|
inlineprivate |
◆ getOccupancyValue() [4/4]
int8_t robot_model_services::MapHelper::getOccupancyValue |
( |
const costmap_2d::Costmap2D & |
costmap, |
|
|
const int32_t & |
mapX, |
|
|
const int32_t & |
mapY |
|
) |
| |
|
inlineprivate |
◆ getOrientation()
◆ getRaytracingMapOccupancyValue() [1/2]
int8_t robot_model_services::MapHelper::getRaytracingMapOccupancyValue |
( |
const SimpleVector3 & |
position | ) |
|
|
inline |
◆ getRaytracingMapOccupancyValue() [2/2]
int8_t robot_model_services::MapHelper::getRaytracingMapOccupancyValue |
( |
const int32_t & |
mapX, |
|
|
const int32_t & |
mapY |
|
) |
| |
|
inline |
◆ getSquaredDistance()
◆ getTranslation()
SimpleVector3 robot_model_services::MapHelper::getTranslation |
( |
| ) |
|
|
inline |
◆ isOccupancyValueAcceptable()
bool robot_model_services::MapHelper::isOccupancyValueAcceptable |
( |
const int8_t & |
occupancyValue | ) |
|
|
inline |
◆ mapReceived()
void robot_model_services::MapHelper::mapReceived |
( |
nav_msgs::OccupancyGrid |
map | ) |
|
|
inlineprivate |
◆ mapToWorldCoordinates() [1/2]
void robot_model_services::MapHelper::mapToWorldCoordinates |
( |
const int32_t & |
x, |
|
|
const int32_t & |
y, |
|
|
SimpleVector3 & |
result |
|
) |
| |
|
inline |
◆ mapToWorldCoordinates() [2/2]
◆ mapToWorldSize()
void robot_model_services::MapHelper::mapToWorldSize |
( |
const double & |
size, |
|
|
double & |
result |
|
) |
| |
|
inline |
◆ setCollisionThreshold()
void robot_model_services::MapHelper::setCollisionThreshold |
( |
int8_t |
thresholdValue | ) |
|
|
inline |
◆ setCostmap()
void robot_model_services::MapHelper::setCostmap |
( |
| ) |
|
|
inlineprivate |
◆ worldToMapCoordinates() [1/2]
void robot_model_services::MapHelper::worldToMapCoordinates |
( |
const SimpleVector3 & |
position, |
|
|
int32_t & |
x, |
|
|
int32_t & |
y |
|
) |
| |
|
inline |
◆ worldToMapCoordinates() [2/2]
◆ worldToMapSize()
void robot_model_services::MapHelper::worldToMapSize |
( |
const double & |
size, |
|
|
double & |
result |
|
) |
| |
|
inline |
◆ mCollisionThreshold
int8_t robot_model_services::MapHelper::mCollisionThreshold |
|
private |
◆ mCostmap
◆ mCostTranslationTable
int8_t robot_model_services::MapHelper::mCostTranslationTable[256] |
|
private |
◆ mDebugHelperPtr
◆ mGetPlanServiceClient
◆ mGlobalNodeHandle
◆ mMap
nav_msgs::OccupancyGrid robot_model_services::MapHelper::mMap |
|
private |
◆ mMapReceived
bool robot_model_services::MapHelper::mMapReceived |
|
private |
◆ mRaytracingMap
nav_msgs::OccupancyGrid robot_model_services::MapHelper::mRaytracingMap |
|
private |
The documentation for this class was generated from the following file:
asr_robot_model_services
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 Mon Feb 28 2022 21:56:02