00001 #ifndef EXPLORATION_PLANNER_H 00002 #define EXPLORATION_PLANNER_H 00003 00004 #define EXPL_TARGET_SET 1 00005 #define EXPL_FINISHED 2 00006 #define EXPL_WAITING 3 00007 #define EXPL_FAILED 4 00008 00009 #include <string> 00010 #include <tf/transform_listener.h> 00011 #include <nav2d_msgs/RobotPose.h> 00012 00013 #include <nav2d_navigator/GridMap.h> 00014 00015 // A list of all other robots, that will subscribe to the other robots topic and update itself 00016 typedef std::map<unsigned int, geometry_msgs::Pose2D> PoseList; 00017 00018 class RobotList 00019 { 00020 public: 00021 RobotList() 00022 { 00023 ros::NodeHandle robotNode; 00024 mOtherRobotsSubscriber = robotNode.subscribe("others", 10, &RobotList::receiveOtherPose, this); 00025 } 00026 00027 void receiveOtherPose(const nav2d_msgs::RobotPose::ConstPtr& msg) 00028 { 00029 mOtherRobots[msg->robot_id] = msg->pose; 00030 } 00031 00032 PoseList getRobots() { return mOtherRobots; } 00033 00034 private: 00035 ros::Subscriber mOtherRobotsSubscriber; 00036 PoseList mOtherRobots; 00037 }; 00038 00039 // The base class for all exploration planners 00040 class ExplorationPlanner 00041 { 00042 public: 00043 virtual ~ExplorationPlanner() {}; 00044 virtual int findExplorationTarget(GridMap* map, unsigned int start, unsigned int &goal) = 0; 00045 00046 }; 00047 00048 #endif