Go to the documentation of this file.
18 #ifndef MAP_ACCESSIBILITY_ANALYSIS_H
19 #define MAP_ACCESSIBILITY_ANALYSIS_H
30 #include <nav_msgs/OccupancyGrid.h>
31 #include <geometry_msgs/Point.h>
32 #include <geometry_msgs/Pose2D.h>
33 #include <nav_msgs/GridCells.h>
44 #include <cob_map_accessibility_analysis/CheckPointAccessibility.h>
45 #include <cob_map_accessibility_analysis/CheckPerimeterAccessibility.h>
46 #include <cob_3d_mapping_msgs/GetApproachPoseForPolygon.h>
49 #include <opencv2/opencv.hpp>
53 #include <pcl/conversions.h>
54 #include <pcl/point_types.h>
56 #include <boost/thread/mutex.hpp>
57 #include <boost/shared_ptr.hpp>
58 #include <boost/tokenizer.hpp>
59 #include <boost/foreach.hpp>
60 #include <boost/algorithm/string.hpp>
86 void mapDataCallback(
const nav_msgs::OccupancyGrid::ConstPtr& map_msg_data);
90 const nav_msgs::GridCells::ConstPtr& inflated_obstacles_data);
97 cob_map_accessibility_analysis::CheckPointAccessibility::Response& res);
101 cob_map_accessibility_analysis::CheckPerimeterAccessibility::Response& res);
105 cob_3d_mapping_msgs::GetApproachPoseForPolygon::Response& res);
159 #endif // MAP_ACCESSIBILITY_ANALYSIS_H
cv::Point getRobotLocationInPixelCoordinates()
bool checkPose2DArrayCallback(cob_map_accessibility_analysis::CheckPointAccessibility::Request &req, cob_map_accessibility_analysis::CheckPointAccessibility::Response &res)
image_transport::ImageTransport * it_
bool checkPolygonCallback(cob_3d_mapping_msgs::GetApproachPoseForPolygon::Request &req, cob_3d_mapping_msgs::GetApproachPoseForPolygon::Response &res)
message_filters::Subscriber< nav_msgs::GridCells > inflated_obstacles_sub_
bool approach_path_accessibility_check_
void dynamicObstaclesInit(ros::NodeHandle &nh)
ros::Subscriber map_msg_sub_
void mapInit(ros::NodeHandle &nh_map)
ros::Duration obstacle_topic_update_delay_
double obstacle_topic_update_rate_
std::string map_link_name_
std::string robot_base_link_name_
ros::ServiceServer map_perimeter_accessibility_check_server_
void obstacleDataCallback(const nav_msgs::GridCells::ConstPtr &obstacles_data)
boost::shared_ptr< message_filters::Synchronizer< InflatedObstaclesSyncPolicy > > inflated_obstacles_sub_sync_
ros::NodeHandle node_handle_
tf::TransformListener tf_listener_
std::vector< geometry_msgs::Point > loadRobotFootprint(XmlRpc::XmlRpcValue &footprint_list)
bool checkPerimeterCallback(cob_map_accessibility_analysis::CheckPerimeterAccessibility::Request &req, cob_map_accessibility_analysis::CheckPerimeterAccessibility::Response &res)
double inverse_map_resolution_
message_filters::Subscriber< nav_msgs::GridCells > obstacles_sub_
message_filters::sync_policies::ApproximateTime< nav_msgs::GridCells, nav_msgs::GridCells > InflatedObstaclesSyncPolicy
MapAccessibilityAnalysisServer(ros::NodeHandle nh)
image_transport::Publisher inflated_map_image_pub_
boost::mutex mutex_inflated_map_
~MapAccessibilityAnalysisServer()
ros::Time last_update_time_obstacles_
ros::ServiceServer map_points_accessibility_check_server_
void inflatedObstacleDataCallback(const nav_msgs::GridCells::ConstPtr &obstacles_data, const nav_msgs::GridCells::ConstPtr &inflated_obstacles_data)
bool publish_inflated_map_
cv::Mat inflated_original_map_
void inflationInit(ros::NodeHandle &nh)
void mapDataCallback(const nav_msgs::OccupancyGrid::ConstPtr &map_msg_data)
ros::ServiceServer map_polygon_accessibility_check_server_