#include <map_accessibility_analysis_server.h>
|
| | MapAccessibilityAnalysisServer (ros::NodeHandle nh) |
| |
| | ~MapAccessibilityAnalysisServer () |
| |
| 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 () |
| |
| MapAccessibilityAnalysisServer::MapAccessibilityAnalysisServer |
( |
ros::NodeHandle |
nh | ) |
|
| MapAccessibilityAnalysisServer::~MapAccessibilityAnalysisServer |
( |
| ) |
|
| bool MapAccessibilityAnalysisServer::checkPerimeterCallback |
( |
cob_map_accessibility_analysis::CheckPerimeterAccessibility::Request & |
req, |
|
|
cob_map_accessibility_analysis::CheckPerimeterAccessibility::Response & |
res |
|
) |
| |
|
protected |
| bool MapAccessibilityAnalysisServer::checkPolygonCallback |
( |
cob_3d_mapping_msgs::GetApproachPoseForPolygon::Request & |
req, |
|
|
cob_3d_mapping_msgs::GetApproachPoseForPolygon::Response & |
res |
|
) |
| |
|
protected |
| bool MapAccessibilityAnalysisServer::checkPose2DArrayCallback |
( |
cob_map_accessibility_analysis::CheckPointAccessibility::Request & |
req, |
|
|
cob_map_accessibility_analysis::CheckPointAccessibility::Response & |
res |
|
) |
| |
|
protected |
| void MapAccessibilityAnalysisServer::dynamicObstaclesInit |
( |
ros::NodeHandle & |
nh | ) |
|
|
protected |
| cv::Point MapAccessibilityAnalysisServer::getRobotLocationInPixelCoordinates |
( |
| ) |
|
|
protected |
| void MapAccessibilityAnalysisServer::inflatedObstacleDataCallback |
( |
const nav_msgs::GridCells::ConstPtr & |
obstacles_data, |
|
|
const nav_msgs::GridCells::ConstPtr & |
inflated_obstacles_data |
|
) |
| |
|
protected |
| void MapAccessibilityAnalysisServer::mapDataCallback |
( |
const nav_msgs::OccupancyGrid::ConstPtr & |
map_msg_data | ) |
|
|
protected |
| void MapAccessibilityAnalysisServer::obstacleDataCallback |
( |
const nav_msgs::GridCells::ConstPtr & |
obstacles_data | ) |
|
|
protected |
| bool MapAccessibilityAnalysisServer::approach_path_accessibility_check_ |
|
protected |
| cv::Mat MapAccessibilityAnalysisServer::inflated_map_ |
|
protected |
| cv::Mat MapAccessibilityAnalysisServer::inflated_original_map_ |
|
protected |
| double MapAccessibilityAnalysisServer::inverse_map_resolution_ |
|
protected |
| ros::Time MapAccessibilityAnalysisServer::last_update_time_obstacles_ |
|
protected |
| bool MapAccessibilityAnalysisServer::map_data_recieved_ |
|
protected |
| std::string MapAccessibilityAnalysisServer::map_link_name_ |
|
protected |
| cv::Point2d MapAccessibilityAnalysisServer::map_origin_ |
|
protected |
| ros::ServiceServer MapAccessibilityAnalysisServer::map_perimeter_accessibility_check_server_ |
|
protected |
| ros::ServiceServer MapAccessibilityAnalysisServer::map_polygon_accessibility_check_server_ |
|
protected |
| double MapAccessibilityAnalysisServer::map_resolution_ |
|
protected |
| boost::mutex MapAccessibilityAnalysisServer::mutex_inflated_map_ |
|
protected |
| ros::Duration MapAccessibilityAnalysisServer::obstacle_topic_update_delay_ |
|
protected |
| double MapAccessibilityAnalysisServer::obstacle_topic_update_rate_ |
|
protected |
| cv::Mat MapAccessibilityAnalysisServer::original_map_ |
|
protected |
| bool MapAccessibilityAnalysisServer::publish_inflated_map_ |
|
protected |
| std::string MapAccessibilityAnalysisServer::robot_base_link_name_ |
|
protected |
| double MapAccessibilityAnalysisServer::robot_radius_ |
|
protected |
The documentation for this class was generated from the following files: