map_accessibility_analysis.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
19 #include <ros/ros.h>
20 
21 //#define __DEBUG_DISPLAYS__
22 
24 {
25 
26 }
27 
29 {
30 
31 }
32 
33 void MapAccessibilityAnalysis::inflateMap(const cv::Mat& original_map, cv::Mat& inflated_map, const int robot_radius_pixel)
34 {
35  cv::erode(original_map, inflated_map, cv::Mat(), cv::Point(-1, -1), robot_radius_pixel);
36 }
37 
38 void MapAccessibilityAnalysis::checkPoses(const std::vector<cv::Point>& points_to_check, std::vector<bool>& accessibility_flags,
39  const cv::Mat& inflated_map, const bool approach_path_accessibility_check, const cv::Point& robot_location)
40 {
41 #ifdef __DEBUG_DISPLAYS__
42  cv::Mat display_map = inflated_map.clone();
43 #endif
44 
45  // find the individual connected areas
46  std::vector<std::vector<cv::Point> > area_contours; // first index=contour index; second index=point index within contour
47  if (approach_path_accessibility_check == true)
48  {
49  cv::Mat inflated_map_copy = inflated_map.clone();
50  cv::findContours(inflated_map_copy, area_contours, cv::RETR_LIST, cv::CHAIN_APPROX_SIMPLE);
51  }
52 
53  for (unsigned int i = 0; i < points_to_check.size(); ++i)
54  {
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)
59  {
60  // check if robot can approach this position
61  if (approach_path_accessibility_check == false ||
62  isApproachPositionAccessible(robot_location, cv::Point(u, v), area_contours) == true)
63  accessibility_flags[i] = true;
64  }
65 
66 #ifdef __DEBUG_DISPLAYS__
67  if (accessibility_flags[i] == false)
68  cv::circle(display_map, cv::Point(u, v), 2, cv::Scalar(32), 10);
69  else
70  cv::circle(display_map, cv::Point(u, v), 2, cv::Scalar(192), 10);
71 #endif
72  }
73 
74 #ifdef __DEBUG_DISPLAYS__
75  cv::imshow("points", display_map);
76  cv::waitKey();
77 #endif
78 }
79 
80 
81 void MapAccessibilityAnalysis::checkPerimeter(std::vector<Pose>& accessible_poses_on_perimeter,
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)
84 {
85 #ifdef __DEBUG_DISPLAYS__
86  cv::Mat display_map = inflated_map.clone();
87 #endif
88 
89  // find the individual connected areas
90  std::vector<std::vector<cv::Point> > area_contours; // first index=contour index; second index=point index within contour
91  if (approach_path_accessibility_check == true)
92  {
93  cv::Mat inflated_map_copy = inflated_map.clone();
94  cv::findContours(inflated_map_copy, area_contours, cv::RETR_LIST, cv::CHAIN_APPROX_SIMPLE);
95  }
96 
97  for (double angle = center.orientation; angle < center.orientation + 2 * CV_PI; angle += rotational_sampling_step)
98  {
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)
105  {
106  // check if robot can approach this position
107  if (approach_path_accessibility_check == false
108  || isApproachPositionAccessible(robot_location, cv::Point(u, v), area_contours) == true)
109  {
110  // add accessible point to results
111  Pose pose;
112  pose.x = x;
113  pose.y = y;
114  pose.orientation = angle + CV_PI;
115  while (pose.orientation > 2 * CV_PI)
116  pose.orientation -= 2 * CV_PI;
117  while (pose.orientation < 0.)
118  pose.orientation += 2 * CV_PI;
119  accessible_poses_on_perimeter.push_back(pose);
120  found_pose = true;
121  }
122  }
123 #ifdef __DEBUG_DISPLAYS__
124  if (found_pose == true)
125  cv::circle(display_map, cv::Point(u, v), 2, cv::Scalar(192), 5);
126  else
127  cv::circle(display_map, cv::Point(u, v), 2, cv::Scalar(32), 5);
128 #endif
129  }
130 
131 #ifdef __DEBUG_DISPLAYS__
132  cv::imshow("perimeter", display_map);
133  cv::waitKey();
134 #endif
135 }
136 
137 
138 bool MapAccessibilityAnalysis::isApproachPositionAccessible(const cv::Point& robotLocation,
139  const cv::Point& potentialApproachPose, std::vector<std::vector<cv::Point> > contours)
140 {
141  // check whether potentialApproachPose and robotLocation are in the same area (=same contour)
142  int contourIndexRobot = -1;
143  int contourIndexPotentialApproachPose = -1;
144  for (unsigned int i = 0; i < contours.size(); i++)
145  {
146  if (0 <= cv::pointPolygonTest(contours[i], potentialApproachPose, false))
147  contourIndexPotentialApproachPose = i;
148  if (0 <= cv::pointPolygonTest(contours[i], robotLocation, false))
149  contourIndexRobot = i;
150  }
151  ROS_DEBUG_STREAM("contourIndexPotentialApproachPose=" << contourIndexPotentialApproachPose
152  << " contourIndexRobot=" << contourIndexRobot);
153  if (contourIndexRobot != contourIndexPotentialApproachPose ||
154  (contourIndexRobot == -1 && contourIndexPotentialApproachPose == -1))
155  return false;
156 
157  return true;
158 }
159 
160 
161 void MapAccessibilityAnalysis::computeClosestPointOnPolygon(const cv::Mat& map_with_polygon,
162  const Pose& pose_p, Pose& closest_point_on_polygon)
163 {
164  double closest_pixel_distance_squared = 1e10;
165  for (int v = 0; v < map_with_polygon.rows; v++)
166  {
167  for (int u = 0; u < map_with_polygon.cols; u++)
168  {
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)
172  {
173  closest_pixel_distance_squared = dist_squared;
174  closest_point_on_polygon.x = u;
175  closest_point_on_polygon.y = v;
176  }
177  }
178  }
179 }
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 &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)
#define ROS_DEBUG_STREAM(args)
#define ROS_INFO_STREAM(args)
void inflateMap(const cv::Mat &original_map, cv::Mat &inflated_map, const int robot_radius_pixel)


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