35 cv::erode(original_map, inflated_map, cv::Mat(), cv::Point(-1, -1), robot_radius_pixel);
39 const cv::Mat& inflated_map,
const bool approach_path_accessibility_check,
const cv::Point& robot_location)
41 #ifdef __DEBUG_DISPLAYS__ 42 cv::Mat display_map = inflated_map.clone();
46 std::vector<std::vector<cv::Point> > area_contours;
47 if (approach_path_accessibility_check ==
true)
49 cv::Mat inflated_map_copy = inflated_map.clone();
50 cv::findContours(inflated_map_copy, area_contours, cv::RETR_LIST, cv::CHAIN_APPROX_SIMPLE);
53 for (
unsigned int i = 0; i < points_to_check.size(); ++i)
55 const int u = points_to_check[i].x;
56 const int v = points_to_check[i].y;
57 ROS_INFO_STREAM(
"Checking accessibility of point (" << u <<
", " << v <<
")px.");
58 if (inflated_map.at<uchar>(v, u) != 0)
61 if (approach_path_accessibility_check ==
false ||
63 accessibility_flags[i] =
true;
66 #ifdef __DEBUG_DISPLAYS__ 67 if (accessibility_flags[i] ==
false)
68 cv::circle(display_map, cv::Point(u, v), 2, cv::Scalar(32), 10);
70 cv::circle(display_map, cv::Point(u, v), 2, cv::Scalar(192), 10);
74 #ifdef __DEBUG_DISPLAYS__ 75 cv::imshow(
"points", display_map);
82 const Pose& center,
const double radius,
const double rotational_sampling_step,
83 const cv::Mat& inflated_map,
const bool approach_path_accessibility_check,
const cv::Point& robot_location)
85 #ifdef __DEBUG_DISPLAYS__ 86 cv::Mat display_map = inflated_map.clone();
90 std::vector<std::vector<cv::Point> > area_contours;
91 if (approach_path_accessibility_check ==
true)
93 cv::Mat inflated_map_copy = inflated_map.clone();
94 cv::findContours(inflated_map_copy, area_contours, cv::RETR_LIST, cv::CHAIN_APPROX_SIMPLE);
99 const double x = center.
x + radius * cos(
angle);
100 const double y = center.
y + radius * sin(
angle);
101 const int u = cvRound(x);
102 const int v = cvRound(y);
103 bool found_pose =
false;
104 if (inflated_map.at<uchar>(v, u) != 0)
107 if (approach_path_accessibility_check ==
false 119 accessible_poses_on_perimeter.push_back(pose);
123 #ifdef __DEBUG_DISPLAYS__ 124 if (found_pose ==
true)
125 cv::circle(display_map, cv::Point(u, v), 2, cv::Scalar(192), 5);
127 cv::circle(display_map, cv::Point(u, v), 2, cv::Scalar(32), 5);
131 #ifdef __DEBUG_DISPLAYS__ 132 cv::imshow(
"perimeter", display_map);
139 const cv::Point& potentialApproachPose, std::vector<std::vector<cv::Point> > contours)
142 int contourIndexRobot = -1;
143 int contourIndexPotentialApproachPose = -1;
144 for (
unsigned int i = 0; i < contours.size(); i++)
146 if (0 <= cv::pointPolygonTest(contours[i], potentialApproachPose,
false))
147 contourIndexPotentialApproachPose = i;
148 if (0 <= cv::pointPolygonTest(contours[i], robotLocation,
false))
149 contourIndexRobot = i;
151 ROS_DEBUG_STREAM(
"contourIndexPotentialApproachPose=" << contourIndexPotentialApproachPose
152 <<
" contourIndexRobot=" << contourIndexRobot);
153 if (contourIndexRobot != contourIndexPotentialApproachPose ||
154 (contourIndexRobot == -1 && contourIndexPotentialApproachPose == -1))
162 const Pose& pose_p,
Pose& closest_point_on_polygon)
164 double closest_pixel_distance_squared = 1e10;
165 for (
int v = 0; v < map_with_polygon.rows; v++)
167 for (
int u = 0; u < map_with_polygon.cols; u++)
169 double dist_squared = 0.;
170 if (map_with_polygon.at<uchar>(v, u) == 128 &&
171 (dist_squared = (pose_p.
x - u) * (pose_p.
x - u) + (pose_p.
y - v) * (pose_p.
y - v)) < closest_pixel_distance_squared)
173 closest_pixel_distance_squared = dist_squared;
174 closest_point_on_polygon.
x = u;
175 closest_point_on_polygon.
y = v;
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)
void computeClosestPointOnPolygon(const cv::Mat &map_with_polygon, const Pose &pose_p, Pose &closest_point_on_polygon)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
bool isApproachPositionAccessible(const cv::Point &robotLocation, const cv::Point &potentialApproachPose, std::vector< std::vector< cv::Point > > contours)
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)
~MapAccessibilityAnalysis()
#define ROS_DEBUG_STREAM(args)
#define ROS_INFO_STREAM(args)
MapAccessibilityAnalysis()
void inflateMap(const cv::Mat &original_map, cv::Mat &inflated_map, const int robot_radius_pixel)