map_accessibility_analysis_server.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 <pcl_ros/point_cloud.h>
20 
21 //#define __DEBUG_DISPLAYS__
22 
24 {
25  // read in parameters
26  ROS_INFO("\n--------------------------------------\nMap Accessibility Analysis "
27  "Parameters:\n--------------------------------------");
28  node_handle_.param("approach_path_accessibility_check", approach_path_accessibility_check_, false); // this setting is overwritten temporarily on receiving the CheckPointAccessibility.srv message
29  ROS_INFO_STREAM("approach_path_accessibility_check = " << approach_path_accessibility_check_);
30  node_handle_.param<std::string>("map_link_name", map_link_name_, "/map");
31  ROS_INFO_STREAM("map_link_name = " << map_link_name_);
32  node_handle_.param<std::string>("robot_base_link_name", robot_base_link_name_, "/base_link");
33  ROS_INFO_STREAM("robot_base_link_name_ = " << robot_base_link_name_);
34  node_handle_.param("obstacle_topic_update_rate", obstacle_topic_update_rate_, 5.0);
35  ROS_INFO_STREAM("obstacle_topic_update_rate = " << obstacle_topic_update_rate_);
38  node_handle_.param("publish_inflated_map", publish_inflated_map_, false);
39  ROS_INFO_STREAM("publish_inflated_map = " << publish_inflated_map_);
40  robot_radius_ = 0.;
41  if (node_handle_.hasParam("/local_costmap_node/costmap/footprint"))
42  {
43  // compute robot radius from footprint
44  XmlRpc::XmlRpcValue footprint_list;
45  node_handle_.getParam("/local_costmap_node/costmap/footprint", footprint_list);
46  std::vector<geometry_msgs::Point> footprint = loadRobotFootprint(footprint_list); // polygonal footprint of the robot in [m]
47  std::stringstream footprint_string;
48  footprint_string << "footprint = [ ";
49  for (unsigned int i = 0; i < footprint.size(); ++i)
50  {
51  robot_radius_ = std::max<double>(robot_radius_, sqrt(footprint[i].x * footprint[i].x + footprint[i].y * footprint[i].y));
52  footprint_string << "[" << footprint[i].x << ", " << footprint[i].y << "] ";
53  }
54  footprint_string << "]";
55  ROS_INFO("%s", footprint_string.str().c_str());
56  }
57  if (robot_radius_ == 0.0)
58  {
59  // if no footprint is set take the robot radius
60  node_handle_.param("/local_costmap_node/costmap/robot_radius", robot_radius_, 0.8);
61  }
62  // hack:
63  robot_radius_ = 0.35;
64  ROS_INFO_STREAM("robot_radius = " << robot_radius_);
65 
66  // receive ground floor map once
68 
69  // then set up dynamic obstacle callbacks
70  // inflationInit(node_handle_);
72 
73  // advertise inflated map image
75  inflated_map_image_pub_ = it_->advertise("inflated_map", 1);
76 
77  // advertise services
79  "map_points_accessibility_check", &MapAccessibilityAnalysisServer::checkPose2DArrayCallback, this);
81  "map_perimeter_accessibility_check", &MapAccessibilityAnalysisServer::checkPerimeterCallback, this);
83  "map_polygon_accessibility_check", &MapAccessibilityAnalysisServer::checkPolygonCallback, this);
84 
85  ROS_INFO("MapPointAccessibilityCheck initialized.");
86 }
87 
89 {
90  if (it_ != 0)
91  delete it_;
92 }
93 
94 std::vector<geometry_msgs::Point> MapAccessibilityAnalysisServer::loadRobotFootprint(XmlRpc::XmlRpcValue& footprint_list)
95 {
96  std::vector<geometry_msgs::Point> footprint;
97  geometry_msgs::Point pt;
98  double scale_factor = 1.0;
99 
100  // grab the footprint from the provided parameter
101  std::string footprint_string;
102  std::vector<std::string> footstring_list;
103  if (footprint_list.getType() == XmlRpc::XmlRpcValue::TypeString)
104  {
105  footprint_string = std::string(footprint_list);
106 
107  // if there's just an empty footprint up there, return
108  if (footprint_string == "[]" || footprint_string == "")
109  return footprint;
110 
111  boost::erase_all(footprint_string, " ");
112 
113  boost::char_separator<char> sep("[]");
114  boost::tokenizer<boost::char_separator<char> > tokens(footprint_string, sep);
115  footstring_list = std::vector<std::string>(tokens.begin(), tokens.end());
116  }
117  // make sure we have a list of lists
118  if (!(footprint_list.getType() == XmlRpc::XmlRpcValue::TypeArray && footprint_list.size() > 2) &&
119  !(footprint_list.getType() == XmlRpc::XmlRpcValue::TypeString && footstring_list.size() > 5))
120  {
121  ROS_FATAL("The footprint must be specified as list of lists on the parameter server, but it was specified as %s",
122  std::string(footprint_list).c_str());
123  throw std::runtime_error("The footprint must be specified as list of lists on the parameter server with at least 3 "
124  "points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
125  }
126 
127  if (footprint_list.getType() == XmlRpc::XmlRpcValue::TypeArray)
128  {
129  for (int i = 0; i < footprint_list.size(); ++i)
130  {
131  // make sure we have a list of lists of size 2
132  XmlRpc::XmlRpcValue point = footprint_list[i];
133  if (!(point.getType() == XmlRpc::XmlRpcValue::TypeArray && point.size() == 2))
134  {
135  ROS_FATAL("The footprint must be specified as list of lists on the parameter server eg: [[x1, y1], [x2, y2], "
136  "..., [xn, yn]], but this spec is not of that form");
137  throw std::runtime_error("The footprint must be specified as list of lists on the parameter server eg: [[x1, "
138  "y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form");
139  }
140 
141  // make sure that the value we're looking at is either a double or an int
142  if (!(point[0].getType() == XmlRpc::XmlRpcValue::TypeInt ||
143  point[0].getType() == XmlRpc::XmlRpcValue::TypeDouble))
144  {
145  ROS_FATAL("Values in the footprint specification must be numbers");
146  throw std::runtime_error("Values in the footprint specification must be numbers");
147  }
148  pt.x = point[0].getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(point[0]) : (double)(point[0]);
149  pt.x *= scale_factor;
150 
151  // make sure that the value we're looking at is either a double or an int
152  if (!(point[1].getType() == XmlRpc::XmlRpcValue::TypeInt ||
153  point[1].getType() == XmlRpc::XmlRpcValue::TypeDouble))
154  {
155  ROS_FATAL("Values in the footprint specification must be numbers");
156  throw std::runtime_error("Values in the footprint specification must be numbers");
157  }
158  pt.y = point[1].getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(point[1]) : (double)(point[1]);
159  pt.y *= scale_factor;
160 
161  footprint.push_back(pt);
162 
163  // node.deleteParam(footprint_param);
164  // std::ostringstream oss;
165  // bool first = true;
166  // BOOST_FOREACH(geometry_msgs::Point p, footprint)
167  // {
168  // if (first)
169  // {
170  // oss << "[[" << p.x << "," << p.y << "]";
171  // first = false;
172  // }
173  // else
174  // {
175  // oss << ",[" << p.x << "," << p.y << "]";
176  // }
177  // }
178  // oss << "]";
179  // node.setParam(footprint_param, oss.str().c_str());
180  // node.setParam("footprint", oss.str().c_str());
181  }
182  }
183  else if (footprint_list.getType() == XmlRpc::XmlRpcValue::TypeString)
184  {
185  std::vector<geometry_msgs::Point> footprint_spec;
186  bool valid_foot = true;
187  BOOST_FOREACH (std::string t, footstring_list)
188  {
189  if (t != ",")
190  {
191  boost::erase_all(t, " ");
192  boost::char_separator<char> pt_sep(",");
193  boost::tokenizer<boost::char_separator<char> > pt_tokens(t, pt_sep);
194  std::vector<std::string> point(pt_tokens.begin(), pt_tokens.end());
195 
196  if (point.size() != 2)
197  {
198  ROS_WARN("Each point must have exactly 2 coordinates");
199  valid_foot = false;
200  break;
201  }
202 
203  std::vector<double> tmp_pt;
204  BOOST_FOREACH (std::string p, point)
205  {
206  std::istringstream iss(p);
207  double temp;
208  if (iss >> temp)
209  {
210  tmp_pt.push_back(temp);
211  }
212  else
213  {
214  ROS_WARN("Each coordinate must convert to a double.");
215  valid_foot = false;
216  break;
217  }
218  }
219  if (!valid_foot)
220  break;
221 
222  geometry_msgs::Point pt;
223  pt.x = tmp_pt[0];
224  pt.y = tmp_pt[1];
225 
226  footprint_spec.push_back(pt);
227  }
228  }
229  if (valid_foot)
230  {
231  footprint = footprint_spec;
232  // node.setParam("footprint", footprint_string);
233  }
234  else
235  {
236  ROS_FATAL("This footprint is not valid it must be specified as a list of lists with at least 3 points, you "
237  "specified %s",
238  footprint_string.c_str());
239  throw std::runtime_error("The footprint must be specified as list of lists on the parameter server with at least "
240  "3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
241  }
242  }
243 
244  return footprint;
245 }
246 
248 {
249  map_data_recieved_ = false;
250  map_msg_sub_ = nh.subscribe<nav_msgs::OccupancyGrid>("map", 1, &MapAccessibilityAnalysisServer::mapDataCallback, this);
251  ROS_INFO("MapPointAccessibilityCheck: Waiting to receive map...");
252  while (map_data_recieved_ == false)
253  ros::spinOnce();
254  ROS_INFO("MapPointAccessibilityCheck: Map received.");
255 }
256 
258 {
259  obstacles_sub_.subscribe(nh, "obstacles", 1);
260  inflated_obstacles_sub_.subscribe(nh, "inflated_obstacles", 1);
261 
265  inflated_obstacles_sub_sync_->registerCallback(
267 }
268 
270 {
271  obstacles_sub_.subscribe(nh, "obstacles", 1);
273 }
274 
275 void MapAccessibilityAnalysisServer::mapDataCallback(const nav_msgs::OccupancyGrid::ConstPtr& map_msg_data)
276 {
277  map_resolution_ = map_msg_data->info.resolution;
279  map_origin_ = cv::Point2d(map_msg_data->info.origin.position.x, map_msg_data->info.origin.position.y);
280  ROS_INFO_STREAM("map resolution: " << map_msg_data->info.resolution);
281 
282  // create original map
283  original_map_ = 255 * cv::Mat::ones(map_msg_data->info.height, map_msg_data->info.width, CV_8UC1);
284  for (unsigned int v = 0, i = 0; v < map_msg_data->info.height; v++)
285  {
286  for (unsigned int u = 0; u < map_msg_data->info.width; u++, i++)
287  {
288  if (map_msg_data->data[i] != 0)
289  original_map_.at<unsigned char>(v, u) = 0;
290  }
291  }
292 
293  // compute inflated static map
294  ROS_INFO_STREAM("inflation thickness: " << cvRound(robot_radius_ * inverse_map_resolution_));
295  inflateMap(original_map_, inflated_original_map_, cvRound(robot_radius_ * inverse_map_resolution_));
296  if (inflated_map_.empty() == true)
297  inflated_map_ = inflated_original_map_; // initial setup (if no obstacle msgs were received yet)
298 
299  map_data_recieved_ = true;
301 }
302 
303 void MapAccessibilityAnalysisServer::inflatedObstacleDataCallback(const nav_msgs::GridCells::ConstPtr& obstacles_data,
304  const nav_msgs::GridCells::ConstPtr& inflated_obstacles_data)
305 {
306  if (obstacle_topic_update_rate_ != 0.0 &&
308  {
309  boost::mutex::scoped_lock lock(mutex_inflated_map_);
310 
312  for (unsigned int i = 0; i < obstacles_data->cells.size(); ++i)
313  inflated_map_.at<uchar>((obstacles_data->cells[i].y - map_origin_.y) * inverse_map_resolution_,
314  (obstacles_data->cells[i].x - map_origin_.x) * inverse_map_resolution_) = 0;
315 
316  for (unsigned int i = 0; i < inflated_obstacles_data->cells.size(); i++)
317  inflated_map_.at<uchar>((inflated_obstacles_data->cells[i].y - map_origin_.y) * inverse_map_resolution_,
318  (inflated_obstacles_data->cells[i].x - map_origin_.x) * inverse_map_resolution_) = 0;
319 
321  }
322 }
323 
324 void MapAccessibilityAnalysisServer::obstacleDataCallback(const nav_msgs::GridCells::ConstPtr& obstacles_data)
325 {
326  if (obstacle_topic_update_rate_ != 0.0 &&
328  {
329  double radius = cvRound(robot_radius_ * inverse_map_resolution_);
330 
331  boost::mutex::scoped_lock lock(mutex_inflated_map_);
332 
334  for (unsigned int i = 0; i < obstacles_data->cells.size(); ++i)
335  {
336  const int u = (obstacles_data->cells[i].x - map_origin_.x) * inverse_map_resolution_;
337  const int v = (obstacles_data->cells[i].y - map_origin_.y) * inverse_map_resolution_;
338  inflated_map_.at<uchar>(v, u) = 0;
339  cv::circle(inflated_map_, cv::Point(u, v), radius, cv::Scalar(0), -1);
340  }
341 
342  if (publish_inflated_map_ == true)
343  {
344  // publish image
345  cv_bridge::CvImage cv_ptr;
346  cv_ptr.image = inflated_map_;
347  cv_ptr.encoding = "mono8";
349  }
350 
352  }
353 }
354 
356  cob_map_accessibility_analysis::CheckPointAccessibility::Request& req,
357  cob_map_accessibility_analysis::CheckPointAccessibility::Response& res)
358 {
359  ROS_INFO("Received request to check accessibility of %u points.", (unsigned int)req.points_to_check.size());
360 
361  // determine robot pose if approach path analysis activated
362  cv::Point robot_location(0, 0);
364  robot_location = getRobotLocationInPixelCoordinates();
365 
366  // prepare request and response data in appropriate format
367  std::vector<cv::Point> points_to_check(req.points_to_check.size());
368  for (size_t i=0; i<req.points_to_check.size(); ++i)
369  points_to_check[i] = cv::Point(cvRound((req.points_to_check[i].x - map_origin_.x) * inverse_map_resolution_),
370  cvRound((req.points_to_check[i].y - map_origin_.y) * inverse_map_resolution_));
371  std::vector<bool> accessibility_flags(req.points_to_check.size(), false);
372 
373  // compute accessibility
374  {
375  boost::mutex::scoped_lock lock(mutex_inflated_map_);
376  checkPoses(points_to_check, accessibility_flags, inflated_map_, req.approach_path_accessibility_check, robot_location);
377  }
378 
379  // prepare return data
380  res.accessibility_flags.resize(req.points_to_check.size());
381  for (size_t i=0; i<accessibility_flags.size(); ++i)
382  res.accessibility_flags[i] = accessibility_flags[i];
383 
384  return true;
385 }
386 
388  cob_map_accessibility_analysis::CheckPerimeterAccessibility::Request& req,
389  cob_map_accessibility_analysis::CheckPerimeterAccessibility::Response& res)
390 {
391  ROS_INFO("Received request to check accessibility of a circle with center (%f,%f), radius %f and sampling step %f.",
392  req.center.x, req.center.y, req.radius, req.rotational_sampling_step);
393 
394  if (req.rotational_sampling_step == 0.0)
395  {
396  req.rotational_sampling_step = 10. / 180. * CV_PI;
397  ROS_WARN("rotational_sampling_step was provided as 0.0 . Automatically changed it to %f.", req.rotational_sampling_step);
398  }
399 
400  // determine robot pose if approach path analysis activated
401  cv::Point robot_location(0, 0);
403  robot_location = getRobotLocationInPixelCoordinates();
404 
405  // prepare request and response data in appropriate format
406  Pose center((req.center.x-map_origin_.x)*inverse_map_resolution_, (req.center.y-map_origin_.y)*inverse_map_resolution_, req.center.theta);
407  std::vector<Pose> accessible_poses_on_perimeter;
408 
409  // compute accessibility
410  {
411  boost::mutex::scoped_lock lock(mutex_inflated_map_);
412  checkPerimeter(accessible_poses_on_perimeter, center, req.radius*inverse_map_resolution_, req.rotational_sampling_step, inflated_map_,
413  approach_path_accessibility_check_, robot_location);
414  }
415 
416  // prepare return data
417  for (size_t i=0; i<accessible_poses_on_perimeter.size(); ++i)
418  {
419  geometry_msgs::Pose2D pose;
420  pose.x = accessible_poses_on_perimeter[i].x*map_resolution_ + map_origin_.x;
421  pose.y = accessible_poses_on_perimeter[i].y*map_resolution_ + map_origin_.y;
422  pose.theta = accessible_poses_on_perimeter[i].orientation;
423  res.accessible_poses_on_perimeter.push_back(pose);
424  }
425 
426  return true;
427 }
428 
429 bool MapAccessibilityAnalysisServer::checkPolygonCallback(cob_3d_mapping_msgs::GetApproachPoseForPolygon::Request& req,
430  cob_3d_mapping_msgs::GetApproachPoseForPolygon::Response& res)
431 {
432  ROS_INFO("Received request to check accessibility around a polygon.");
433 
434  // determine robot pose if approach path analysis activated
435  cv::Point robot_location(0, 0);
437  robot_location = getRobotLocationInPixelCoordinates();
438 
439  // copy contours
440  std::vector<std::vector<cv::Point> > polygon_contours;
441  for (unsigned int i = 0; i < req.polygon.points.size(); i++)
442  {
443  if (req.polygon.holes[i] == false)
444  {
445  pcl::PointCloud<pcl::PointXYZ> pc;
446  pcl::fromROSMsg(req.polygon.points[i], pc);
447  std::vector<cv::Point> p_vec(pc.size());
448  for (unsigned int j = 0; j < pc.size(); j++)
449  {
450  p_vec[j] = convertFromMeterToPixelCoordinates<cv::Point>(Pose(pc.points[j].x, pc.points[j].y, 0), map_origin_, inverse_map_resolution_);
451  }
452  polygon_contours.push_back(p_vec);
453  }
454  }
455 
456  // compute inflated polygon
457  cv::Mat polygon_expanded = 255 * cv::Mat::ones(original_map_.rows, original_map_.cols, original_map_.type());
458  cv::drawContours(polygon_expanded, polygon_contours, -1, cv::Scalar(128), cv::FILLED);
459  cv::erode(polygon_expanded, polygon_expanded, cv::Mat(), cv::Point(-1, -1), cvRound(robot_radius_ * inverse_map_resolution_));
460 
461  // combine inflated polygon with inflated map
462  cv::Mat inflated_map;
463  {
464  boost::mutex::scoped_lock lock(mutex_inflated_map_);
465  inflated_map = cv::min(polygon_expanded, inflated_map_);
466  }
467 #ifdef __DEBUG_DISPLAYS__
468  cv::imshow("inflated polygon map", inflated_map);
469  cv::waitKey();
470 #endif
471 
472  // find the individual connected areas
473  std::vector<std::vector<cv::Point> > area_contours; // first index=contour index; second index=point index within contour
475  {
476  cv::Mat inflated_map_copy = inflated_map.clone();
477  cv::findContours(inflated_map_copy, area_contours, cv::RETR_LIST, cv::CHAIN_APPROX_SIMPLE);
478  }
479 
480 // iterate through all white points and consider those as potential approach poses that have an expanded table pixel in
481 // their neighborhood
482 #ifdef __DEBUG_DISPLAYS__
483  cv::Mat map_expanded_copy = inflated_map.clone();
484  cv::drawContours(map_expanded_copy, area_contours, -1, cv::Scalar(128, 128, 128, 128), 2);
485 #endif
486  for (int y = 1; y < inflated_map.rows - 1; y++)
487  {
488  for (int x = 1; x < inflated_map.cols - 1; x++)
489  {
490  if (inflated_map.at<uchar>(y, x) == 255)
491  {
492  bool close_to_polygon = false;
493  for (int ky = -1; ky <= 1; ky++)
494  for (int kx = -1; kx <= 1; kx++)
495  {
496  if (inflated_map.at<uchar>(y + ky, x + kx) == 128)
497  {
498  close_to_polygon = true;
499  break;
500  }
501  }
502  if (close_to_polygon == true)
503  {
504  // check if robot can approach this position
505  if (approach_path_accessibility_check_ == false ||
506  isApproachPositionAccessible(robot_location, cv::Point(x, y), area_contours) == true)
507  {
508  geometry_msgs::Pose pose;
509  Pose pose_p(x, y, 0);
510  Pose pose_m = convertFromPixelCoordinatesToMeter<Pose>(pose_p, map_origin_, map_resolution_);
511  pose.position.x = pose_m.x;
512  pose.position.y = pose_m.y;
513  pose.position.z = 0;
514 
515  Pose closest_point_on_polygon;
516  computeClosestPointOnPolygon(inflated_map, pose_p, closest_point_on_polygon);
517 
518  tf::quaternionTFToMsg(tf::createQuaternionFromYaw(atan2(closest_point_on_polygon.y - pose_p.y,
519  closest_point_on_polygon.x - pose_p.x)),
520  pose.orientation);
521  // tf::quaternionTFToMsg(tf::createQuaternionFromYaw(atan2(-dy.at<float>(y,x),-dx.at<float>(y,x))),
522  // pose.orientation);
523  res.approach_poses.poses.push_back(pose);
524  }
525 
526 #ifdef __DEBUG_DISPLAYS__
527  // display found contours
528  cv::circle(map_expanded_copy, robot_location, 3, cv::Scalar(200, 200, 200, 200), -1);
529  cv::circle(map_expanded_copy, cv::Point(x, y), 3, cv::Scalar(200, 200, 200, 200), -1);
530 // ROS_DEBUG_STREAM(" x=" << x << " y=" << y);
531 #endif
532  }
533  }
534  }
535  }
536 #ifdef __DEBUG_DISPLAYS__
537  cv::imshow("contour areas", map_expanded_copy);
538  cv::waitKey();
539 #endif
540 
541  return true;
542 }
543 
545 {
546  tf::StampedTransform transform;
547  try
548  {
549  ros::Time request_time = ros::Time(0);
552  }
553  catch (tf::TransformException ex)
554  {
555  ROS_ERROR("[registration] : %s", ex.what());
556  return cv::Point(0, 0);
557  }
558  tf::Vector3 pose = transform.getOrigin();
559  cv::Point robot_location = convertFromMeterToPixelCoordinates<cv::Point>(Pose(pose.x(), pose.y(), 0), map_origin_, inverse_map_resolution_);
560 
561  return robot_location;
562 }
563 
564 
565 int main(int argc, char** argv)
566 {
567  ros::init(argc, argv, "map_accessibility_analysis_server");
568 
569  ros::NodeHandle nh;
570 
571  MapAccessibilityAnalysisServer map_accessibility_analysis(nh);
572 
573  ros::spin();
574 
575  return 0;
576 }
#define ROS_FATAL(...)
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)
bool checkPolygonCallback(cob_3d_mapping_msgs::GetApproachPoseForPolygon::Request &req, cob_3d_mapping_msgs::GetApproachPoseForPolygon::Response &res)
void computeClosestPointOnPolygon(const cv::Mat &map_with_polygon, const Pose &pose_p, Pose &closest_point_on_polygon)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
boost::shared_ptr< message_filters::Synchronizer< InflatedObstaclesSyncPolicy > > inflated_obstacles_sub_sync_
int size() const
void inflatedObstacleDataCallback(const nav_msgs::GridCells::ConstPtr &obstacles_data, const nav_msgs::GridCells::ConstPtr &inflated_obstacles_data)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string encoding
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
bool checkPerimeterCallback(cob_map_accessibility_analysis::CheckPerimeterAccessibility::Request &req, cob_map_accessibility_analysis::CheckPerimeterAccessibility::Response &res)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Type const & getType() const
#define ROS_WARN(...)
ROSCPP_DECL void spin(Spinner &spinner)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
static Quaternion createQuaternionFromYaw(double yaw)
void publish(const sensor_msgs::Image &message) const
#define ROS_INFO(...)
bool checkPose2DArrayCallback(cob_map_accessibility_analysis::CheckPointAccessibility::Request &req, cob_map_accessibility_analysis::CheckPointAccessibility::Response &res)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
message_filters::sync_policies::ApproximateTime< nav_msgs::GridCells, nav_msgs::GridCells > InflatedObstaclesSyncPolicy
TFSIMD_FORCE_INLINE const tfScalar & y() const
int main(int argc, char **argv)
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)
message_filters::Subscriber< nav_msgs::GridCells > inflated_obstacles_sub_
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
#define ROS_INFO_STREAM(args)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
bool getParam(const std::string &key, std::string &s) const
void obstacleDataCallback(const nav_msgs::GridCells::ConstPtr &obstacles_data)
void mapDataCallback(const nav_msgs::OccupancyGrid::ConstPtr &map_msg_data)
static Time now()
bool hasParam(const std::string &key) const
void inflateMap(const cv::Mat &original_map, cv::Mat &inflated_map, const int robot_radius_pixel)
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
sensor_msgs::ImagePtr toImageMsg() const
std::vector< geometry_msgs::Point > loadRobotFootprint(XmlRpc::XmlRpcValue &footprint_list)
message_filters::Subscriber< nav_msgs::GridCells > obstacles_sub_
Connection registerCallback(const C &callback)


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