target.h
Go to the documentation of this file.
1 #ifndef TARGET_H
2 #define TARGET_H
3 
4 #include <ros/ros.h>
5 #include <geometry_msgs/Pose.h>
6 
7 using namespace std;
8 using namespace ros;
9 
13 typedef enum {
14  TARGET_UNKNOWN = 0, // unknown target
15  TARGET_KNOWN, // target found by another CPS
16  TARGET_TRACKED, // target found by this CPS
17  TARGET_ASSIGNED, // target assigned to any CPS
18  TARGET_LOST, // target lost by any CPS
19  TARGET_DONE // target completed by any CPS
21 
25 class target
26 {
27 public:
31  target ();
32 
36  target (const target& t);
37 
43  target (unsigned int id, target_state_t state);
44 
51  target (unsigned int id, target_state_t state, geometry_msgs::Pose pose);
52 
60  target (unsigned int id, target_state_t state, geometry_msgs::Pose pose, Time stamp);
61 
65  ~target ();
66 
71  geometry_msgs::Pose get_pose ();
72 
77  target_state_t get_state ();
78 
83  bool lost ();
84 
89  void operator= (const target& t);
90 
97  void update (target_state_t state, geometry_msgs::Pose pose, Time stamp);
98 
99 private:
104 
108  int id;
109 
114 
118  geometry_msgs::Pose pose;
119 
124 
129 
134 };
135 
136 #endif // TARGET_H
int id
The ID of this target. Negative IDs are invalid.
Definition: target.h:108
Time stamp
Time stamp of latest update of the target.
Definition: target.h:123
Duration timeout
The time in seconds after which a target transitions into the state TARGET_LOST when no target update...
Definition: target.h:128
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
target_state_t state
State of the target.
Definition: target.h:113
geometry_msgs::Pose pose
Position of the target.
Definition: target.h:118
A target that is monitored by the CPSs.
Definition: target.h:25
Rate * rate
The loop rate object for running the behavior control loops at a specific frequency.
Definition: target.h:133
target_state_t
An enumeration for the state of a target.
Definition: target.h:13
NodeHandle nh
A node handle for the main ROS node.
Definition: target.h:103
geometry_msgs::Pose pose
Current position of the CPS.


target_monitor
Author(s): Micha Sende
autogenerated on Tue Jan 19 2021 03:30:07