ExplorationPlanner.h
Go to the documentation of this file.
1 #ifndef EXPLORATION_PLANNER_H
2 #define EXPLORATION_PLANNER_H
3 
4 #define EXPL_TARGET_SET 1
5 #define EXPL_FINISHED 2
6 #define EXPL_WAITING 3
7 #define EXPL_FAILED 4
8 
9 #include <string>
10 #include <tf/transform_listener.h>
11 #include <nav2d_msgs/RobotPose.h>
12 
14 
15 // A list of all other robots, that will subscribe to the other robots topic and update itself
16 typedef std::map<unsigned int, geometry_msgs::Pose2D> PoseList;
17 
18 class RobotList
19 {
20 public:
22  {
23  ros::NodeHandle robotNode;
24  mOtherRobotsSubscriber = robotNode.subscribe("others", 10, &RobotList::receiveOtherPose, this);
25  }
26 
27  void receiveOtherPose(const nav2d_msgs::RobotPose::ConstPtr& msg)
28  {
29  mOtherRobots[msg->robot_id] = msg->pose;
30  }
31 
33 
34 private:
37 };
38 
39 // The base class for all exploration planners
41 {
42 public:
43  virtual ~ExplorationPlanner() {};
44  virtual int findExplorationTarget(GridMap* map, unsigned int start, unsigned int &goal) = 0;
45 
46 };
47 
48 #endif
PoseList getRobots()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Definition: GridMap.h:7
void receiveOtherPose(const nav2d_msgs::RobotPose::ConstPtr &msg)
ros::Subscriber mOtherRobotsSubscriber
std::map< unsigned int, geometry_msgs::Pose2D > PoseList
PoseList mOtherRobots


nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Tue Nov 7 2017 06:02:48