Newer
Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
#ifndef POI_MANAGER_H
#define POI_MANAGER_H
#include <list>
#include <homer_mapnav_msgs/PointOfInterest.h>
#include <homer_mapnav_msgs/ModifyPOI.h>
#include <ros/ros.h>
/** @class PoiManager
* @author Malte Knauf, David Gossow
* @brief This class manages the List of points of interest (POIs)
*
* This class keeps a list of all POIs within the current map. It provides the usual functions
* to edit the list.
*/
class PoiManager {
public:
/** The constructor of the class. */
PoiManager(ros::NodeHandle* nh);
/** constructor initializing the poi list */
PoiManager( std::vector< homer_mapnav_msgs::PointOfInterest > pois );
/** Does nothing. */
~PoiManager() {}
/** Adds a new POI to the list if no POI with the same name exists
* @param poi pointer to the PointOfInterest message with the POI to be added
* @return true if successful, false otherwise
*/
bool addPointOfInterest( const homer_mapnav_msgs::PointOfInterest::ConstPtr& poi );
/** Replaces a POI with a new one
* @param poi pointer with the PointOfInterest to be inserted
* the POI with the same ID as the new one is first deleted
* @return true if the old POI was found and could be deleted
* false otherwise
*/
bool modifyPointOfInterest( const homer_mapnav_msgs::ModifyPOI::ConstPtr& poi );
/** Deletes a POI with a certain name from the list
* @param name Name of the POI to be deleted
* @return true if the POI was found and could be deleted
* false otherwise
*/
bool deletePointOfInterest( std::string name );
/**
* @brief place the current poi list
* @param poilist new poi list
*/
void replacePOIList(std::vector<homer_mapnav_msgs::PointOfInterest> poilist);
/** Returns current POI list
* @return the POI list
*/
std::vector< homer_mapnav_msgs::PointOfInterest > getList();
private:
/** Looks for POI with name in the list
* @param name Name of the POI
*/
bool poiExists( std::string name );
/**
* @brief Publishes a PointsOfInterest Message with current POIs
*/
void broadcastPoiList();
/** The copy constructor of the class.
* It's kept private, because it will never be used.
*/
PoiManager( const PoiManager& instance );
/** Holds the POI vector */
std::vector< homer_mapnav_msgs::PointOfInterest > m_Pois;
/** publisher that publishes the current poi list */
ros::Publisher m_POIsPublisher;
};
#endif