4 #include <unordered_map> 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> 63 geometry_msgs::Transform
transform (geometry_msgs::Pose p1, geometry_msgs::Pose p2)
const;
targets()
Constructor that initializes the private member variables.
void publish_event(string event, int id)
Publish a target position event.
unordered_map< unsigned int, shared_ptr< target > > target_map
A map holding ID and target object of all known targets.
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.
void uuid_callback(const swarmros::String::ConstPtr &msg)
Callback function to receive the UUID from the communication library.
geometry_msgs::Transform transform(geometry_msgs::Pose p1, geometry_msgs::Pose p2) const
Compute the transformation between two poses.
Publisher target_done_pub
Publisher for transmitting information about completed targets locally to other nodes and remotely to...
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...
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...
void simulate()
Read simulated targets from parameter file.
string cps
The UUID of the CPS that owns this class instance.
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...
NodeHandle nh
A node handle for the main ROS node.
Publisher target_found_pub
Publisher for transmitting information about found targets locally to other nodes and remotely to oth...
A collection of target objects that are searched, tracked, and rescued by the CPSs.
Publisher tracking_pub
Publisher for transmitting target tracking information in simulation.
target_state_t
An enumeration for the state of a target.
Publisher target_update_pub
Publisher for transmitting updated information about targets locally to other nodes and remotely to o...
geometry_msgs::Pose pose
Current position of the CPS.