targets.h
Go to the documentation of this file.
1 #ifndef TARGETS_H
2 #define TARGETS_H
3 
4 #include <unordered_map>
5 #include <tf2/utils.h>
6 #include <geometry_msgs/Pose.h>
7 #include <geometry_msgs/Transform.h>
8 #include <swarmros/String.h>
9 #include <cpswarm_msgs/TargetTracking.h>
10 #include <cpswarm_msgs/TargetPositionEvent.h>
11 #include "target.h"
12 
16 class targets
17 {
18 public:
22  targets ();
23 
28  void publish (unsigned int id);
29 
33  void simulate ();
34 
39  void update (geometry_msgs::Pose pose);
40 
47  void update (cpswarm_msgs::TargetPositionEvent msg, target_state_t state);
48 
49 private:
55  void publish_event (string event, int id);
56 
63  geometry_msgs::Transform transform (geometry_msgs::Pose p1, geometry_msgs::Pose p2) const;
64 
69  void uuid_callback (const swarmros::String::ConstPtr& msg);
70 
75 
80 
85 
90 
95 
100 
104  unordered_map<unsigned int, shared_ptr<target>> target_map;
105 
109  unordered_map<unsigned int, shared_ptr<target>> simulated_targets;
110 
114  string cps;
115 
119  double fov;
120 };
121 
122 #endif // TARGETS_H
targets()
Constructor that initializes the private member variables.
Definition: targets.cpp:3
void publish_event(string event, int id)
Publish a target position event.
Definition: targets.cpp:134
unordered_map< unsigned int, shared_ptr< target > > target_map
A map holding ID and target object of all known targets.
Definition: targets.h:104
double fov
Range of the target tracking camera in meter. It is used to simulate target detection. Targets within this distance are detected by the CPS.
Definition: targets.h:119
void uuid_callback(const swarmros::String::ConstPtr &msg)
Callback function to receive the UUID from the communication library.
Definition: targets.cpp:193
geometry_msgs::Transform transform(geometry_msgs::Pose p1, geometry_msgs::Pose p2) const
Compute the transformation between two poses.
Definition: targets.cpp:163
Publisher target_done_pub
Publisher for transmitting information about completed targets locally to other nodes and remotely to...
Definition: targets.h:99
void publish(unsigned int id)
Publish a target position event for the given target.
Publisher target_lost_pub
Publisher for transmitting information about lost targets locally to other nodes and remotely to othe...
Definition: targets.h:94
unordered_map< unsigned int, shared_ptr< target > > simulated_targets
A map holding ID and target object of simulated targets, including the ones not yet found...
Definition: targets.h:109
void simulate()
Read simulated targets from parameter file.
Definition: targets.cpp:39
string cps
The UUID of the CPS that owns this class instance.
Definition: targets.h:114
void update(geometry_msgs::Pose pose)
Update the state of all targets. If no update has been received for a target within a fixed period...
Definition: targets.cpp:62
NodeHandle nh
A node handle for the main ROS node.
Definition: targets.h:74
Publisher target_found_pub
Publisher for transmitting information about found targets locally to other nodes and remotely to oth...
Definition: targets.h:84
A collection of target objects that are searched, tracked, and rescued by the CPSs.
Definition: targets.h:16
Publisher tracking_pub
Publisher for transmitting target tracking information in simulation.
Definition: targets.h:79
target_state_t
An enumeration for the state of a target.
Definition: target.h:13
Publisher target_update_pub
Publisher for transmitting updated information about targets locally to other nodes and remotely to o...
Definition: targets.h:89
geometry_msgs::Pose pose
Current position of the CPS.


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