#include <map_accessibility_analysis.h>
|
void | checkPerimeter (std::vector< Pose > &accessible_poses_on_perimeter, const Pose ¢er, const double radius, const double rotational_sampling_step, const cv::Mat &inflated_map, const bool approach_path_accessibility_check, const cv::Point &robot_location) |
|
void | checkPoses (const std::vector< cv::Point > &points_to_check, std::vector< bool > &accessibility_flags, const cv::Mat &inflated_map, const bool approach_path_accessibility_check, const cv::Point &robot_location) |
|
template<class T > |
T | convertFromMeterToPixelCoordinates (const Pose &pose, const cv::Point2d &map_origin, const double inverse_map_resolution) |
|
template<class T > |
T | convertFromPixelCoordinatesToMeter (const Pose &pose, const cv::Point2d &map_origin, const double map_resolution) |
|
void | inflateMap (const cv::Mat &original_map, cv::Mat &inflated_map, const int robot_radius_pixel) |
|
| MapAccessibilityAnalysis () |
|
| ~MapAccessibilityAnalysis () |
|
MapAccessibilityAnalysis::MapAccessibilityAnalysis |
( |
| ) |
|
MapAccessibilityAnalysis::~MapAccessibilityAnalysis |
( |
| ) |
|
void MapAccessibilityAnalysis::checkPerimeter |
( |
std::vector< Pose > & |
accessible_poses_on_perimeter, |
|
|
const Pose & |
center, |
|
|
const double |
radius, |
|
|
const double |
rotational_sampling_step, |
|
|
const cv::Mat & |
inflated_map, |
|
|
const bool |
approach_path_accessibility_check, |
|
|
const cv::Point & |
robot_location |
|
) |
| |
This function checks the accessibility of points on a perimeter around a center point.
- Parameters
-
accessible_poses_on_radius | The returned set of accessible poses on the perimeter of the given circle, in map coordinates [px,px,rad] |
center | Center of the circle whose perimeter should be checked for accessibility, in map coordinates [px,px,rad] |
radius | Radius of the circle whose perimeter should be checked for accessibility, in [px] |
rotational_sampling_step | Rotational sampling step width for checking points on the perimeter, in [rad] |
inflated_map | The map that is to be tested with walls and obstacles inflated by the robot radius |
approach_path_accessibility_check | If true, there must be a path from robot_location to a goal position in order to report accessibility |
robot_location | [Optional] The current robot position in the map if approach_path_accessibility_check=true, in map coordinates [px] |
Definition at line 81 of file map_accessibility_analysis.cpp.
void MapAccessibilityAnalysis::checkPoses |
( |
const std::vector< cv::Point > & |
points_to_check, |
|
|
std::vector< bool > & |
accessibility_flags, |
|
|
const cv::Mat & |
inflated_map, |
|
|
const bool |
approach_path_accessibility_check, |
|
|
const cv::Point & |
robot_location |
|
) |
| |
This function checks a vector of map positions for their accessibility.
- Parameters
-
points_to_check | All the map positions whose accessibility shall be tested, in map coordinates [px] |
accessibility_flags | Response to each map position whether it is accessible (true) or not (false) |
inflated_map | The map that is to be tested with walls and obstacles inflated by the robot radius |
approach_path_accessibility_check | If true, there must be a path from robot_location to a goal position in order to report accessibility |
robot_location | [Optional] The current robot position in the map if approach_path_accessibility_check=true, in map coordinates [px] |
Definition at line 38 of file map_accessibility_analysis.cpp.
void MapAccessibilityAnalysis::computeClosestPointOnPolygon |
( |
const cv::Mat & |
map_with_polygon, |
|
|
const Pose & |
pose_p, |
|
|
Pose & |
closest_point_on_polygon |
|
) |
| |
|
protected |
template<class T >
T MapAccessibilityAnalysis::convertFromMeterToPixelCoordinates |
( |
const Pose & |
pose, |
|
|
const cv::Point2d & |
map_origin, |
|
|
const double |
inverse_map_resolution |
|
) |
| |
|
inline |
template<class T >
T MapAccessibilityAnalysis::convertFromPixelCoordinatesToMeter |
( |
const Pose & |
pose, |
|
|
const cv::Point2d & |
map_origin, |
|
|
const double |
map_resolution |
|
) |
| |
|
inline |
void MapAccessibilityAnalysis::inflateMap |
( |
const cv::Mat & |
original_map, |
|
|
cv::Mat & |
inflated_map, |
|
|
const int |
robot_radius_pixel |
|
) |
| |
Inflates the walls and obstacles in a map by the radius of the robot, resulting in a map of accessible areas for the robot.
- Parameters
-
robot_radius_pixel | Provides the robot radius converted to pixels in the given maps, in [px] |
Definition at line 33 of file map_accessibility_analysis.cpp.
bool MapAccessibilityAnalysis::isApproachPositionAccessible |
( |
const cv::Point & |
robotLocation, |
|
|
const cv::Point & |
potentialApproachPose, |
|
|
std::vector< std::vector< cv::Point > > |
contours |
|
) |
| |
|
protected |
The documentation for this class was generated from the following files: