Classes | Public Member Functions | Protected Member Functions | List of all members
MapAccessibilityAnalysis Class Reference

#include <map_accessibility_analysis.h>

Inheritance diagram for MapAccessibilityAnalysis:
Inheritance graph
[legend]

Classes

struct  Pose
 

Public Member Functions

void 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)
 
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 >
convertFromMeterToPixelCoordinates (const Pose &pose, const cv::Point2d &map_origin, const double inverse_map_resolution)
 
template<class 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 ()
 

Protected Member Functions

void computeClosestPointOnPolygon (const cv::Mat &map_with_polygon, const Pose &pose_p, Pose &closest_point_on_polygon)
 
bool isApproachPositionAccessible (const cv::Point &robotLocation, const cv::Point &potentialApproachPose, std::vector< std::vector< cv::Point > > contours)
 

Detailed Description

Definition at line 24 of file map_accessibility_analysis.h.

Constructor & Destructor Documentation

MapAccessibilityAnalysis::MapAccessibilityAnalysis ( )

Definition at line 23 of file map_accessibility_analysis.cpp.

MapAccessibilityAnalysis::~MapAccessibilityAnalysis ( )

Definition at line 28 of file map_accessibility_analysis.cpp.

Member Function Documentation

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_radiusThe returned set of accessible poses on the perimeter of the given circle, in map coordinates [px,px,rad]
centerCenter of the circle whose perimeter should be checked for accessibility, in map coordinates [px,px,rad]
radiusRadius of the circle whose perimeter should be checked for accessibility, in [px]
rotational_sampling_stepRotational sampling step width for checking points on the perimeter, in [rad]
inflated_mapThe map that is to be tested with walls and obstacles inflated by the robot radius
approach_path_accessibility_checkIf 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_checkAll the map positions whose accessibility shall be tested, in map coordinates [px]
accessibility_flagsResponse to each map position whether it is accessible (true) or not (false)
inflated_mapThe map that is to be tested with walls and obstacles inflated by the robot radius
approach_path_accessibility_checkIf 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

Definition at line 161 of file map_accessibility_analysis.cpp.

template<class T >
T MapAccessibilityAnalysis::convertFromMeterToPixelCoordinates ( const Pose pose,
const cv::Point2d &  map_origin,
const double  inverse_map_resolution 
)
inline

Definition at line 88 of file map_accessibility_analysis.h.

template<class T >
T MapAccessibilityAnalysis::convertFromPixelCoordinatesToMeter ( const Pose pose,
const cv::Point2d &  map_origin,
const double  map_resolution 
)
inline

Definition at line 97 of file map_accessibility_analysis.h.

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_pixelProvides 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

Definition at line 138 of file map_accessibility_analysis.cpp.


The documentation for this class was generated from the following files:


cob_map_accessibility_analysis
Author(s): Richard Bormann
autogenerated on Sat Oct 24 2020 03:50:48