include
nav2d_navigator
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
13
#include <
nav2d_navigator/GridMap.h
>
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
:
21
RobotList
()
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
32
PoseList
getRobots
() {
return
mOtherRobots
; }
33
34
private
:
35
ros::Subscriber
mOtherRobotsSubscriber
;
36
PoseList
mOtherRobots
;
37
};
38
39
// The base class for all exploration planners
40
class
ExplorationPlanner
41
{
42
public
:
43
virtual
~ExplorationPlanner
() {};
44
virtual
int
findExplorationTarget
(
GridMap
* map,
unsigned
int
start,
unsigned
int
&goal) = 0;
45
46
};
47
48
#endif
RobotList::RobotList
RobotList()
Definition:
ExplorationPlanner.h:21
GridMap
Definition:
GridMap.h:7
RobotList
Definition:
ExplorationPlanner.h:18
RobotList::receiveOtherPose
void receiveOtherPose(const nav2d_msgs::RobotPose::ConstPtr &msg)
Definition:
ExplorationPlanner.h:27
ExplorationPlanner::~ExplorationPlanner
virtual ~ExplorationPlanner()
Definition:
ExplorationPlanner.h:43
GridMap.h
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ExplorationPlanner
Definition:
ExplorationPlanner.h:40
transform_listener.h
RobotList::getRobots
PoseList getRobots()
Definition:
ExplorationPlanner.h:32
RobotList::mOtherRobotsSubscriber
ros::Subscriber mOtherRobotsSubscriber
Definition:
ExplorationPlanner.h:35
PoseList
std::map< unsigned int, geometry_msgs::Pose2D > PoseList
Definition:
ExplorationPlanner.h:16
RobotList::mOtherRobots
PoseList mOtherRobots
Definition:
ExplorationPlanner.h:36
ExplorationPlanner::findExplorationTarget
virtual int findExplorationTarget(GridMap *map, unsigned int start, unsigned int &goal)=0
ros::NodeHandle
ros::Subscriber
nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Wed Mar 2 2022 00:37:37