Go to the documentation of this file.00001
00039 #ifndef SEGBOT_LOGICAL_TRANSLATOR_G54K6X7H
00040 #define SEGBOT_LOGICAL_TRANSLATOR_G54K6X7H
00041
00042 #include <ros/ros.h>
00043 #include <boost/shared_ptr.hpp>
00044
00045 #include <bwi_mapper/map_loader.h>
00046 #include <bwi_planning_common/structures.h>
00047 #include <bwi_tools/point.h>
00048 #include <nav_msgs/GetPlan.h>
00049
00050 namespace segbot_logical_translator {
00051
00052 class SegbotLogicalTranslator {
00053
00054 public:
00055
00056 SegbotLogicalTranslator();
00057
00058 bool isDoorOpen(size_t idx);
00059
00060 bool getApproachPoint(size_t idx,
00061 const bwi::Point2f& current_location,
00062 bwi::Point2f& point, float &yaw);
00063
00064 bool getThroughDoorPoint(size_t idx,
00065 const bwi::Point2f& current_location,
00066 bwi::Point2f& point, float& yaw);
00067
00068 bool isRobotFacingDoor(
00069 const bwi::Point2f& current_location,
00070 float yaw, float threshold, size_t idx);
00071 bool isRobotBesideDoor(
00072 const bwi::Point2f& current_location,
00073 float yaw, float threshold, size_t idx);
00074
00075 inline bool getObjectApproachLocation(const std::string& object_name,
00076 geometry_msgs::Pose& pose) {
00077 if (object_approach_map_.find(object_name) ==
00078 object_approach_map_.end()) {
00079 return false;
00080 }
00081 pose = object_approach_map_[object_name];
00082 return true;
00083 }
00084
00085 size_t getLocationIdx(
00086 const bwi::Point2f& current_location);
00087
00088 inline size_t getLocationIdx(
00089 const std::string& loc_str) const {
00090 for (size_t i = 0; i < locations_.size(); ++i) {
00091 if (locations_[i] == loc_str) {
00092 return i;
00093 }
00094 }
00095 return (size_t)-1;
00096 }
00097
00098 inline size_t getDoorIdx(const std::string& door_str) const {
00099 for (size_t i = 0; i < doors_.size(); ++i) {
00100 if (doors_[i].name == door_str) {
00101 return i;
00102 }
00103 }
00104 return (size_t)-1;
00105 }
00106
00107 inline std::string getLocationString(size_t idx) const {
00108 if (idx >= locations_.size())
00109 return "";
00110 return locations_[idx];
00111 }
00112
00113 inline std::string getDoorString(size_t idx) const {
00114 if (idx >= doors_.size())
00115 return "";
00116 return doors_[idx].name;
00117 }
00118
00119 inline size_t getNumDoors() const {
00120 return doors_.size();
00121 }
00122
00123 protected:
00124
00125 std::string global_frame_id_;
00126
00127 std::vector<bwi_planning_common::Door> doors_;
00128 std::vector<std::string> locations_;
00129 std::vector<int32_t> location_map_;
00130 std::map<std::string, geometry_msgs::Pose> object_approach_map_;
00131
00132 boost::shared_ptr <bwi_mapper::MapLoader> mapper_;
00133 nav_msgs::MapMetaData info_;
00134
00135 boost::shared_ptr<ros::NodeHandle> nh_;
00136 ros::ServiceClient make_plan_client_;
00137
00138 };
00139
00140 }
00141
00142 #endif