26 ROS_INFO(
"\n--------------------------------------\nMap Accessibility Analysis " 27 "Parameters:\n--------------------------------------");
33 ROS_INFO_STREAM(
"robot_base_link_name_ = " << robot_base_link_name_);
47 std::stringstream footprint_string;
48 footprint_string <<
"footprint = [ ";
49 for (
unsigned int i = 0; i < footprint.size(); ++i)
52 footprint_string <<
"[" << footprint[i].x <<
", " << footprint[i].y <<
"] ";
54 footprint_string <<
"]";
55 ROS_INFO(
"%s", footprint_string.str().c_str());
85 ROS_INFO(
"MapPointAccessibilityCheck initialized.");
96 std::vector<geometry_msgs::Point> footprint;
97 geometry_msgs::Point pt;
98 double scale_factor = 1.0;
101 std::string footprint_string;
102 std::vector<std::string> footstring_list;
105 footprint_string = std::string(footprint_list);
108 if (footprint_string ==
"[]" || footprint_string ==
"")
111 boost::erase_all(footprint_string,
" ");
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());
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]]");
129 for (
int i = 0; i < footprint_list.
size(); ++i)
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");
145 ROS_FATAL(
"Values in the footprint specification must be numbers");
146 throw std::runtime_error(
"Values in the footprint specification must be numbers");
149 pt.x *= scale_factor;
155 ROS_FATAL(
"Values in the footprint specification must be numbers");
156 throw std::runtime_error(
"Values in the footprint specification must be numbers");
159 pt.y *= scale_factor;
161 footprint.push_back(pt);
185 std::vector<geometry_msgs::Point> footprint_spec;
186 bool valid_foot =
true;
187 BOOST_FOREACH (std::string t, footstring_list)
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());
196 if (point.size() != 2)
198 ROS_WARN(
"Each point must have exactly 2 coordinates");
203 std::vector<double> tmp_pt;
204 BOOST_FOREACH (std::string p, point)
206 std::istringstream iss(p);
210 tmp_pt.push_back(temp);
214 ROS_WARN(
"Each coordinate must convert to a double.");
222 geometry_msgs::Point pt;
226 footprint_spec.push_back(pt);
231 footprint = footprint_spec;
236 ROS_FATAL(
"This footprint is not valid it must be specified as a list of lists with at least 3 points, you " 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]]");
251 ROS_INFO(
"MapPointAccessibilityCheck: Waiting to receive map...");
254 ROS_INFO(
"MapPointAccessibilityCheck: Map received.");
279 map_origin_ = cv::Point2d(map_msg_data->info.origin.position.x, map_msg_data->info.origin.position.y);
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++)
286 for (
unsigned int u = 0; u < map_msg_data->info.width; u++, i++)
288 if (map_msg_data->data[i] != 0)
304 const nav_msgs::GridCells::ConstPtr& inflated_obstacles_data)
312 for (
unsigned int i = 0; i < obstacles_data->cells.size(); ++i)
316 for (
unsigned int i = 0; i < inflated_obstacles_data->cells.size(); i++)
334 for (
unsigned int i = 0; i < obstacles_data->cells.size(); ++i)
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_;
339 cv::circle(
inflated_map_, cv::Point(u, v), radius, cv::Scalar(0), -1);
356 cob_map_accessibility_analysis::CheckPointAccessibility::Request& req,
357 cob_map_accessibility_analysis::CheckPointAccessibility::Response& res)
359 ROS_INFO(
"Received request to check accessibility of %u points.", (
unsigned int)req.points_to_check.size());
362 cv::Point robot_location(0, 0);
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)
371 std::vector<bool> accessibility_flags(req.points_to_check.size(),
false);
376 checkPoses(points_to_check, accessibility_flags,
inflated_map_, req.approach_path_accessibility_check, robot_location);
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];
388 cob_map_accessibility_analysis::CheckPerimeterAccessibility::Request& req,
389 cob_map_accessibility_analysis::CheckPerimeterAccessibility::Response& res)
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);
394 if (req.rotational_sampling_step == 0.0)
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);
401 cv::Point robot_location(0, 0);
407 std::vector<Pose> accessible_poses_on_perimeter;
417 for (
size_t i=0; i<accessible_poses_on_perimeter.size(); ++i)
419 geometry_msgs::Pose2D pose;
422 pose.theta = accessible_poses_on_perimeter[i].orientation;
423 res.accessible_poses_on_perimeter.push_back(pose);
430 cob_3d_mapping_msgs::GetApproachPoseForPolygon::Response& res)
432 ROS_INFO(
"Received request to check accessibility around a polygon.");
435 cv::Point robot_location(0, 0);
440 std::vector<std::vector<cv::Point> > polygon_contours;
441 for (
unsigned int i = 0; i < req.polygon.points.size(); i++)
443 if (req.polygon.holes[i] ==
false)
445 pcl::PointCloud<pcl::PointXYZ> pc;
447 std::vector<cv::Point> p_vec(pc.size());
448 for (
unsigned int j = 0; j < pc.size(); j++)
452 polygon_contours.push_back(p_vec);
458 cv::drawContours(polygon_expanded, polygon_contours, -1, cv::Scalar(128), cv::FILLED);
462 cv::Mat inflated_map;
467 #ifdef __DEBUG_DISPLAYS__ 468 cv::imshow(
"inflated polygon map", inflated_map);
473 std::vector<std::vector<cv::Point> > area_contours;
476 cv::Mat inflated_map_copy = inflated_map.clone();
477 cv::findContours(inflated_map_copy, area_contours, cv::RETR_LIST, cv::CHAIN_APPROX_SIMPLE);
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);
486 for (
int y = 1; y < inflated_map.rows - 1; y++)
488 for (
int x = 1; x < inflated_map.cols - 1; x++)
490 if (inflated_map.at<uchar>(y, x) == 255)
492 bool close_to_polygon =
false;
493 for (
int ky = -1; ky <= 1; ky++)
494 for (
int kx = -1; kx <= 1; kx++)
496 if (inflated_map.at<uchar>(y + ky, x + kx) == 128)
498 close_to_polygon =
true;
502 if (close_to_polygon ==
true)
508 geometry_msgs::Pose pose;
509 Pose pose_p(x, y, 0);
511 pose.position.
x = pose_m.
x;
512 pose.position.y = pose_m.
y;
515 Pose closest_point_on_polygon;
519 closest_point_on_polygon.
x - pose_p.x)),
523 res.approach_poses.poses.push_back(pose);
526 #ifdef __DEBUG_DISPLAYS__ 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);
536 #ifdef __DEBUG_DISPLAYS__ 537 cv::imshow(
"contour areas", map_expanded_copy);
555 ROS_ERROR(
"[registration] : %s", ex.what());
556 return cv::Point(0, 0);
561 return robot_location;
565 int main(
int argc,
char** argv)
567 ros::init(argc, argv,
"map_accessibility_analysis_server");
cv::Point getRobotLocationInPixelCoordinates()
ros::ServiceServer map_polygon_accessibility_check_server_
double obstacle_topic_update_rate_
image_transport::ImageTransport * it_
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_
image_transport::Publisher inflated_map_image_pub_
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)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
void mapInit(ros::NodeHandle &nh_map)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
void dynamicObstaclesInit(ros::NodeHandle &nh)
ros::Time last_update_time_obstacles_
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)
ros::Duration obstacle_topic_update_delay_
Type const & getType() const
ROSCPP_DECL void spin(Spinner &spinner)
TFSIMD_FORCE_INLINE const tfScalar & x() const
tf::TransformListener tf_listener_
static Quaternion createQuaternionFromYaw(double yaw)
void publish(const sensor_msgs::Image &message) const
bool checkPose2DArrayCallback(cob_map_accessibility_analysis::CheckPointAccessibility::Request &req, cob_map_accessibility_analysis::CheckPointAccessibility::Response &res)
bool param(const std::string ¶m_name, T ¶m_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)
MapAccessibilityAnalysisServer(ros::NodeHandle nh)
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)
message_filters::Subscriber< nav_msgs::GridCells > inflated_obstacles_sub_
bool approach_path_accessibility_check_
ros::Subscriber map_msg_sub_
~MapAccessibilityAnalysisServer()
ros::ServiceServer map_points_accessibility_check_server_
bool publish_inflated_map_
std::string map_link_name_
#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)
ros::ServiceServer map_perimeter_accessibility_check_server_
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)
std::string robot_base_link_name_
boost::mutex mutex_inflated_map_
ros::NodeHandle node_handle_
bool hasParam(const std::string &key) const
cv::Mat inflated_original_map_
void inflateMap(const cv::Mat &original_map, cv::Mat &inflated_map, const int robot_radius_pixel)
ROSCPP_DECL void spinOnce()
double inverse_map_resolution_
sensor_msgs::ImagePtr toImageMsg() const
std::vector< geometry_msgs::Point > loadRobotFootprint(XmlRpc::XmlRpcValue &footprint_list)
void inflationInit(ros::NodeHandle &nh)
message_filters::Subscriber< nav_msgs::GridCells > obstacles_sub_
Connection registerCallback(const C &callback)