segbot_logical_translator.cpp
Go to the documentation of this file.
00001 
00037 #include <tf/transform_datatypes.h>
00038 
00039 #include <boost/algorithm/string/classification.hpp>
00040 #include <boost/algorithm/string/join.hpp>
00041 #include <boost/algorithm/string/split.hpp>
00042 #include <boost/filesystem.hpp>
00043 #include <boost/foreach.hpp>
00044 #include <bwi_mapper/map_inflator.h>
00045 #include <bwi_mapper/map_loader.h>
00046 #include <bwi_mapper/map_utils.h>
00047 #include <bwi_mapper/point_utils.h>
00048 
00049 #include <segbot_logical_translator/segbot_logical_translator.h>
00050 
00051 namespace segbot_logical_translator {
00052 
00053   SegbotLogicalTranslator::SegbotLogicalTranslator() : make_plan_client_initialized_(false), initialized_(false) {
00054     nh_.reset(new ros::NodeHandle);
00055     ros::param::param<std::string>("~global_frame_id", global_frame_id_, "level_mux/map");
00056   }
00057 
00058   bool SegbotLogicalTranslator::initialize() {
00059     ROS_INFO_STREAM("SegbotLogicalTranslator: Initializing...");
00060 
00061     std::string map_file, data_directory;
00062     std::vector<std::string> required_parameters;
00063     if (!ros::param::get("~map_file", map_file)) {
00064       required_parameters.push_back("~map_file");
00065     }
00066     if (!ros::param::get("~data_directory", data_directory)) {
00067       required_parameters.push_back("~data_directory");
00068     }
00069     if (required_parameters.size() != 0) {
00070       std::string message = "SegbotLogicalTranslator: Required parameters [" +
00071         boost::algorithm::join(required_parameters, ", ") + "] missing!";
00072       ROS_FATAL_STREAM(message);
00073       throw std::runtime_error(message);
00074     }
00075 
00076     std::string door_file = bwi_planning_common::getDoorsFileLocationFromDataDirectory(data_directory);
00077     ROS_INFO_STREAM("SegbotLogicalTranslator: Reading door file: " + door_file);
00078     bwi_planning_common::readDoorFile(door_file, doors_);
00079 
00080     std::string location_file = bwi_planning_common::getLocationsFileLocationFromDataDirectory(data_directory);
00081     ROS_INFO_STREAM("SegbotLogicalTranslator: Reading locations file: " + location_file);
00082     bwi_planning_common::readLocationFile(location_file, locations_, location_map_);
00083 
00084     std::string object_file = bwi_planning_common::getObjectsFileLocationFromDataDirectory(data_directory);
00085     ROS_INFO_STREAM("SegbotLogicalTranslator: Checking if objects file exists: " + object_file);
00086     if (boost::filesystem::exists(object_file)) {
00087       ROS_INFO_STREAM("SegbotLogicalTranslator:   Objects file exists. Reading now!");
00088       bwi_planning_common::readObjectApproachFile(object_file, object_approach_map_);
00089     }
00090 
00091     bwi_mapper::MapLoader mapper(map_file);
00092     mapper.getMap(map_);
00093     map_.header.stamp = ros::Time::now();
00094     map_.header.frame_id = global_frame_id_;
00095     info_ = map_.info;
00096 
00097     std::string map_with_doors_file = bwi_planning_common::getDoorsMapLocationFromDataDirectory(data_directory);
00098     mapper = bwi_mapper::MapLoader(map_with_doors_file);
00099     mapper.getMap(map_with_doors_);
00100     map_with_doors_.header.stamp = ros::Time::now();
00101     map_with_doors_.header.frame_id = global_frame_id_;
00102 
00103     // Inflating map by 20cm should get rid of any tiny paths to the goal.
00104     bwi_mapper::inflateMap(0.2, map_with_doors_, inflated_map_with_doors_);
00105 
00106     // We'll do lazy initialization of the approachable space. Just clear it for now, and we'll populate it as
00107     // necessary.
00108     door_approachable_space_1_.clear();
00109     door_approachable_space_2_.clear();
00110     object_approachable_space_.clear();
00111 
00112     initialized_ = true;
00113     return true;
00114   }
00115 
00116   bool SegbotLogicalTranslator::isDoorOpen(size_t idx) {
00117 
00118     if (!initialized_) {
00119       ROS_ERROR_STREAM("SegbotLogicalTranslator : requesting data without being initialized!");
00120       return false;
00121     }
00122 
00123     if (idx > doors_.size()) {
00124       return false;
00125     }
00126 
00127     bwi_mapper::Point2f start_pt, goal_pt;
00128     float start_yaw, goal_yaw;
00129 
00130     start_pt = doors_[idx].approach_points[0];
00131     goal_pt = doors_[idx].approach_points[1];
00132     start_yaw = doors_[idx].approach_yaw[0];
00133     goal_yaw = doors_[idx].approach_yaw[1];
00134 
00135     nav_msgs::GetPlan srv;
00136     geometry_msgs::PoseStamped &start = srv.request.start;
00137     geometry_msgs::PoseStamped &goal = srv.request.goal;
00138     start.header.frame_id = goal.header.frame_id = global_frame_id_;
00139     start.header.stamp = goal.header.stamp = ros::Time::now();
00140 
00141     start.pose.position.x = start_pt.x;
00142     start.pose.position.y = start_pt.y;
00143     start.pose.position.z = 0;
00144     start.pose.orientation = tf::createQuaternionMsgFromYaw(start_yaw);
00145 
00146     goal.pose.position.x = goal_pt.x;
00147     goal.pose.position.y = goal_pt.y;
00148     goal.pose.position.z = 0;
00149     goal.pose.orientation = tf::createQuaternionMsgFromYaw(goal_yaw);
00150     srv.request.tolerance = -1.0f;//0.5 + 1e-6;
00151 
00152     float min_distance = cv::norm(start_pt - goal_pt);
00153 
00154     int counter = 0;
00155 
00156     if (!make_plan_client_initialized_) {
00157       ROS_INFO_STREAM("SegbotLogicalTranslator: Waiting for make_plan service..");
00158       make_plan_client_ = nh_->serviceClient<nav_msgs::GetPlan>("move_base/make_plan");
00159       make_plan_client_.waitForExistence();
00160       ROS_INFO_STREAM("SegbotLogicalTranslator: make_plan service found!");
00161       make_plan_client_initialized_ = true;
00162     }
00163 
00164     for( int  i = 0; i < 3 ; i++){
00165       if (make_plan_client_.call(srv)) {
00166         if (srv.response.plan.poses.size() != 0) {
00167           // Valid plan received. Check if plan distance seems reasonable
00168           float distance = 0;
00169           geometry_msgs::Point old_pt =
00170             srv.response.plan.poses[0].pose.position;
00171           for (size_t i = 1; i < srv.response.plan.poses.size(); ++i) {
00172             geometry_msgs::Point current_pt =
00173               srv.response.plan.poses[i].pose.position;
00174             distance += sqrt(pow(current_pt.x - old_pt.x, 2) +
00175                              pow(current_pt.y - old_pt.y, 2));
00176             old_pt = current_pt;
00177           }
00178           if (distance < 3 * min_distance) {
00179             //return true;
00180             counter++;
00181           } else {
00182             //return false; // returned path probably through some other door
00183             counter = 0;
00184           }
00185         } else {
00186           //return false; // this is ok. it means the door is closed
00187           counter = 0;
00188         }
00189       } else {
00190         //return false; // shouldn't be here. the service has failed
00191         counter = 0;
00192       }
00193     }
00194     if (counter == 3){
00195       // we have see the door open 3 consequitive times
00196       return true;
00197     } else {
00198       return false;
00199     }
00200   }
00201 
00202   bool SegbotLogicalTranslator::getApproachPoint(size_t idx,
00203       const bwi_mapper::Point2f& current_location,
00204       bwi_mapper::Point2f& point, float &yaw) {
00205 
00206     if (!initialized_) {
00207       ROS_ERROR_STREAM("SegbotLogicalTranslator : requesting data without being initialized!");
00208       return false;
00209     }
00210 
00211     if (idx > doors_.size()) {
00212       return false;
00213     }
00214 
00215     // See if we've calculated the approachable space for this door.
00216     if (door_approachable_space_1_.find(idx) == door_approachable_space_1_.end()) {
00217       const bwi_planning_common::Door& door = doors_[idx];
00218       const bwi_mapper::Point2d approach_pt_1(bwi_mapper::toGrid(door.approach_points[0], info_));
00219       door_approachable_space_1_[idx] = boost::shared_ptr<bwi_mapper::PathFinder>(new bwi_mapper::PathFinder(inflated_map_with_doors_, approach_pt_1));
00220     }
00221     if (door_approachable_space_2_.find(idx) == door_approachable_space_2_.end()) {
00222       const bwi_planning_common::Door& door = doors_[idx];
00223       const bwi_mapper::Point2d approach_pt_2(bwi_mapper::toGrid(door.approach_points[1], info_));
00224       door_approachable_space_2_[idx] = boost::shared_ptr<bwi_mapper::PathFinder>(new bwi_mapper::PathFinder(inflated_map_with_doors_, approach_pt_2));
00225     }
00226 
00227     // Find the approach point to which we can find a path. If both approach points can be reached, fine the approach
00228     // point which is closer.
00229     bwi_mapper::Point2d grid(bwi_mapper::toGrid(current_location, info_));
00230     int distance_1 = door_approachable_space_1_[idx]->getManhattanDistance(grid);
00231     int distance_2 = door_approachable_space_2_[idx]->getManhattanDistance(grid);
00232     if (distance_1 >= 0 || distance_2 >= 0) {
00233       if (distance_1 >= 0 && (distance_1 < distance_2 || distance_2 < 0)) {
00234         point = doors_[idx].approach_points[0];
00235         yaw = doors_[idx].approach_yaw[0];
00236       } else {
00237         point = doors_[idx].approach_points[1];
00238         yaw = doors_[idx].approach_yaw[1];
00239       }
00240       return true;
00241     }
00242 
00243     /* The door is not approachable from the current location */
00244     return false;
00245   }
00246 
00247   bool SegbotLogicalTranslator::isObjectApproachable(const std::string& object_name,
00248                                                      const bwi_mapper::Point2f& current_location) {
00249 
00250     if (!initialized_) {
00251       ROS_ERROR_STREAM("SegbotLogicalTranslator : requesting data without being initialized!");
00252       return false;
00253     }
00254 
00255     if (object_approachable_space_.find(object_name) == object_approachable_space_.end()) {
00256       const geometry_msgs::Pose& object_pose = object_approach_map_[object_name];
00257       const bwi_mapper::Point2d approach_pt(bwi_mapper::toGrid(bwi_mapper::Point2f(object_pose.position.x,
00258                                                                                    object_pose.position.y),
00259                                                                info_));
00260       object_approachable_space_[object_name] = boost::shared_ptr<bwi_mapper::PathFinder>(new bwi_mapper::PathFinder(inflated_map_with_doors_, approach_pt));
00261     }
00262 
00263     bwi_mapper::Point2d grid_pt(bwi_mapper::toGrid(current_location, info_));
00264     return object_approachable_space_[object_name]->pathExists(grid_pt);
00265   }
00266 
00267   bool SegbotLogicalTranslator::getThroughDoorPoint(size_t idx,
00268       const bwi_mapper::Point2f& current_location,
00269       bwi_mapper::Point2f& point, float& yaw) {
00270 
00271     if (!initialized_) {
00272       ROS_ERROR_STREAM("SegbotLogicalTranslator : requesting data without being initialized!");
00273       return false;
00274     }
00275 
00276     if (idx > doors_.size()) {
00277       return false;
00278     }
00279 
00280     bwi_mapper::Point2f approach_point;
00281 
00282     float unused_approach_yaw;
00283     bool door_approachable = getApproachPoint(idx, current_location, approach_point, unused_approach_yaw);
00284     if (door_approachable) {
00285       if (approach_point.x == doors_[idx].approach_points[0].x &&
00286           approach_point.y == doors_[idx].approach_points[0].y) {
00287         point = doors_[idx].approach_points[1];
00288         yaw = doors_[idx].approach_yaw[1] + M_PI;
00289       } else {
00290         point = doors_[idx].approach_points[0];
00291         yaw = doors_[idx].approach_yaw[0] + M_PI;
00292       }
00293       return true;
00294     }
00295 
00296     return false;
00297   }
00298 
00299   bool SegbotLogicalTranslator::isRobotFacingDoor(
00300       const bwi_mapper::Point2f& current_location,
00301       float yaw, float threshold, size_t idx) {
00302 
00303     if (!initialized_) {
00304       ROS_ERROR_STREAM("SegbotLogicalTranslator : requesting data without being initialized!");
00305       return false;
00306     }
00307 
00308     bwi_mapper::Point2f& center_pt = doors_[idx].door_center;
00309     if (bwi_mapper::getMagnitude(center_pt - current_location) >
00310         threshold) {
00311       return false;
00312     }
00313 
00314     bwi_mapper::Point2f diff_pt = center_pt - current_location;
00315     float orientation_to_door = atan2f(diff_pt.y, diff_pt.x);
00316     while (orientation_to_door > yaw + M_PI) orientation_to_door -= 2*M_PI;
00317     while (orientation_to_door <= yaw - M_PI) orientation_to_door += 2*M_PI;
00318     if (fabs(orientation_to_door - yaw) > M_PI / 3) {
00319       return false;
00320     }
00321 
00322     return true;
00323   }
00324 
00325   bool SegbotLogicalTranslator::isRobotBesideDoor(
00326       const bwi_mapper::Point2f& current_location,
00327       float yaw, float threshold, size_t idx) {
00328 
00329     if (!initialized_) {
00330       ROS_ERROR_STREAM("SegbotLogicalTranslator : requesting data without being initialized!");
00331       return false;
00332     }
00333 
00334     bwi_mapper::Point2f& center_pt = doors_[idx].door_center;
00335     if (bwi_mapper::getMagnitude(center_pt - current_location) >
00336         threshold) {
00337       return false;
00338     }
00339 
00340     return true;
00341   }
00342 
00343   size_t SegbotLogicalTranslator::getLocationIdx(
00344       const bwi_mapper::Point2f& current_location) {
00345 
00346     if (!initialized_) {
00347       ROS_ERROR_STREAM("SegbotLogicalTranslator : requesting data without being initialized!");
00348       return false;
00349     }
00350 
00351     bwi_mapper::Point2f grid = bwi_mapper::toGrid(current_location, info_);
00352     size_t map_idx = MAP_IDX(info_.width, (int) grid.x, (int) grid.y);
00353     if (map_idx > location_map_.size()) {
00354       return (size_t) -1;
00355     }
00356     return (size_t) location_map_[map_idx];
00357 
00358   }
00359 
00360 } /* namespace segbot_logical_translator */


segbot_logical_translator
Author(s): Piyush Khandelwal
autogenerated on Thu Aug 27 2015 15:11:22