A collection of target objects that are searched, tracked, and rescued by the CPSs.
More...
#include <targets.h>
|
void | publish (unsigned int id) |
| Publish a target position event for the given target. More...
|
|
void | simulate () |
| Read simulated targets from parameter file. More...
|
|
| targets () |
| Constructor that initializes the private member variables. More...
|
|
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, its state will change to TARGET_LOST. This needs to be called periodically. More...
|
|
void | update (cpswarm_msgs::TargetPositionEvent msg, target_state_t state) |
| Update the information of a target. More...
|
|
|
void | publish_event (string event, int id) |
| Publish a target position event. More...
|
|
geometry_msgs::Transform | transform (geometry_msgs::Pose p1, geometry_msgs::Pose p2) const |
| Compute the transformation between two poses. More...
|
|
void | uuid_callback (const swarmros::String::ConstPtr &msg) |
| Callback function to receive the UUID from the communication library. More...
|
|
|
string | cps |
| The UUID of the CPS that owns this class instance. More...
|
|
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. More...
|
|
NodeHandle | nh |
| A node handle for the main ROS node. More...
|
|
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. More...
|
|
Publisher | target_done_pub |
| Publisher for transmitting information about completed targets locally to other nodes and remotely to other CPSs. More...
|
|
Publisher | target_found_pub |
| Publisher for transmitting information about found targets locally to other nodes and remotely to other CPSs. More...
|
|
Publisher | target_lost_pub |
| Publisher for transmitting information about lost targets locally to other nodes and remotely to other CPSs. More...
|
|
unordered_map< unsigned int, shared_ptr< target > > | target_map |
| A map holding ID and target object of all known targets. More...
|
|
Publisher | target_update_pub |
| Publisher for transmitting updated information about targets locally to other nodes and remotely to other CPSs. More...
|
|
Publisher | tracking_pub |
| Publisher for transmitting target tracking information in simulation. More...
|
|
A collection of target objects that are searched, tracked, and rescued by the CPSs.
Definition at line 16 of file targets.h.
Constructor that initializes the private member variables.
Definition at line 3 of file targets.cpp.
void targets::publish |
( |
unsigned int |
id | ) |
|
Publish a target position event for the given target.
- Parameters
-
void targets::publish_event |
( |
string |
event, |
|
|
int |
id |
|
) |
| |
|
private |
Publish a target position event.
- Parameters
-
event | The name of the event. |
id | The ID of the target. |
Definition at line 134 of file targets.cpp.
void targets::simulate |
( |
| ) |
|
Read simulated targets from parameter file.
Definition at line 39 of file targets.cpp.
geometry_msgs::Transform targets::transform |
( |
geometry_msgs::Pose |
p1, |
|
|
geometry_msgs::Pose |
p2 |
|
) |
| const |
|
private |
Compute the transformation between two poses.
- Parameters
-
p1 | The first pose. |
p2 | The second pose. |
- Returns
- The computed transformation.
Definition at line 163 of file targets.cpp.
void targets::update |
( |
geometry_msgs::Pose |
pose | ) |
|
Update the state of all targets. If no update has been received for a target within a fixed period, its state will change to TARGET_LOST. This needs to be called periodically.
- Parameters
-
pose | The current position of the CPS. |
Definition at line 62 of file targets.cpp.
void targets::update |
( |
cpswarm_msgs::TargetPositionEvent |
msg, |
|
|
target_state_t |
state |
|
) |
| |
Update the information of a target.
- Parameters
-
msg | The target position event message. |
state | The target state. |
Definition at line 91 of file targets.cpp.
void targets::uuid_callback |
( |
const swarmros::String::ConstPtr & |
msg | ) |
|
|
private |
Callback function to receive the UUID from the communication library.
- Parameters
-
Definition at line 193 of file targets.cpp.
The UUID of the CPS that owns this class instance.
Definition at line 114 of file targets.h.
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 at line 119 of file targets.h.
A node handle for the main ROS node.
Definition at line 74 of file targets.h.
unordered_map<unsigned int, shared_ptr<target> > targets::simulated_targets |
|
private |
A map holding ID and target object of simulated targets, including the ones not yet found.
Definition at line 109 of file targets.h.
Publisher for transmitting information about completed targets locally to other nodes and remotely to other CPSs.
Definition at line 99 of file targets.h.
Publisher for transmitting information about found targets locally to other nodes and remotely to other CPSs.
Definition at line 84 of file targets.h.
Publisher for transmitting information about lost targets locally to other nodes and remotely to other CPSs.
Definition at line 94 of file targets.h.
unordered_map<unsigned int, shared_ptr<target> > targets::target_map |
|
private |
A map holding ID and target object of all known targets.
Definition at line 104 of file targets.h.
Publisher for transmitting updated information about targets locally to other nodes and remotely to other CPSs.
Definition at line 89 of file targets.h.
Publisher for transmitting target tracking information in simulation.
Definition at line 79 of file targets.h.
The documentation for this class was generated from the following files: