targets.cpp
Go to the documentation of this file.
1 #include "lib/targets.h"
2 
4 {
5  // read parameters
6  double loop_rate;
7  nh.param(this_node::getName() + "/loop_rate", loop_rate, 5.0);
8  Rate rate(loop_rate);
9  int queue_size;
10  nh.param(this_node::getName() + "/queue_size", queue_size, 10);
11  nh.param(this_node::getName() + "/fov", fov, 0.5);
12 
13  // uuid of this cps
14  cps = "";
15 
16  // read done targets from parameter server
17  vector<int> done;
18  nh.getParam(this_node::getNamespace() + "/targets_done", done);
19  for (int t : done) {
20  target_map.emplace(piecewise_construct, forward_as_tuple(t), forward_as_tuple(make_shared<target>(t, TARGET_DONE)));
21  }
22 
23  // publishers and subscribers
24  tracking_pub = nh.advertise<cpswarm_msgs::TargetTracking>("target_tracking", queue_size, true);
25  Subscriber uuid_sub = nh.subscribe("bridge/uuid", queue_size, &targets::uuid_callback, this);
26 
27  // init uuid
28  while (ok() && cps == "") {
29  rate.sleep();
30  spinOnce();
31  }
32 }
33 
35 {
36  // read all potential targets from parameter file
37  vector<double> targets_x;
38  vector<double> targets_y;
39  nh.getParam(this_node::getName() + "/targets_x", targets_x);
40  nh.getParam(this_node::getName() + "/targets_y", targets_y);
41  if (targets_x.size() != targets_y.size()) {
42  ROS_FATAL("Invalid targets specified! Exiting...");
43  shutdown();
44  }
45  else if (targets_x.size() < 1)
46  ROS_INFO("There are no targets!");
47  for (int i = 0; i < targets_x.size(); ++i) {
48  ROS_DEBUG("Target %d at [%.2f, %.2f]", i, targets_x[i], targets_y[i]);
49  geometry_msgs::Pose new_target_pose;
50  new_target_pose.position.x = targets_x[i];
51  new_target_pose.position.y = targets_y[i];
52  new_target_pose.orientation.w = 1;
53  simulated_targets.emplace(piecewise_construct, forward_as_tuple(i), forward_as_tuple(make_shared<target>(i, TARGET_UNKNOWN, new_target_pose)));
54  }
55 }
56 
57 void targets::update (geometry_msgs::Pose pose)
58 {
59  // check if a target is lost
60  for (auto t : target_map) {
61  // update target and inform others in case target is lost
62  t.second->lost();
63  }
64 
65  // check if a new target is found in simulation
66  for (auto t : simulated_targets) {
67  // target pose
68  geometry_msgs::Pose t_pose = t.second->get_pose();
69 
70  ROS_DEBUG("Target %d distance %.2f < %.2f", t.first, hypot(pose.position.x - t_pose.position.x, pose.position.y - t_pose.position.y), fov);
71 
72  // target is within camera fov
73  if (hypot(pose.position.x - t_pose.position.x, pose.position.y - t_pose.position.y) <= fov) {
74  // publish tracking information
75  cpswarm_msgs::TargetTracking track;
76  track.header.stamp = Time::now();
77  track.id = t.first;
78  track.tf = transform(pose, t_pose);
79  tracking_pub.publish(track);
80  }
81  }
82 }
83 
84 void targets::update (cpswarm_msgs::TargetPositionEvent msg, target_state_t state)
85 {
86  // determine target pose
87  geometry_msgs::Pose pose;
88  pose = msg.pose.pose;
89 
90  ROS_DEBUG("Target %d at [%.2f, %.2f]", msg.id, pose.position.x, pose.position.y);
91 
92  // update existing target
93  if (target_map.count(msg.id) > 0) {
94  target_map[msg.id]->update(state, pose, msg.header.stamp);
95  }
96 
97  // add new target
98  else {
99  target_map.emplace(piecewise_construct, forward_as_tuple(msg.id), forward_as_tuple(make_shared<target>(msg.id, state, pose, msg.header.stamp)));
100  }
101 }
102 
103 geometry_msgs::Transform targets::transform (geometry_msgs::Pose p1, geometry_msgs::Pose p2) const
104 {
105  // orientation of first point
106  tf2::Quaternion orientation1;
107  tf2::fromMsg(p1.orientation, orientation1);
108 
109  // relative coordinates of second point
110  double dx = p2.position.x - p1.position.x;
111  double dy = p2.position.y - p1.position.y;
112  double distance = hypot(dx, dy);
113  double direction = (M_PI / 2.0) - tf2::getYaw(orientation1) + atan2(dy, dx);
114 
115  // compute transform
116  geometry_msgs::Transform tf;
117 
118  // translation
119  tf.translation.x = -distance * cos(direction); // x is inverted in tracking camera tf
120  tf.translation.y = distance * sin(direction);
121 
122  // rotation
123  p1.orientation.w *= -1; // invert p1
124  tf2::fromMsg(p1.orientation, orientation1);
125  tf2::Quaternion orientation2;
126  tf2::fromMsg(p2.orientation, orientation2);
127  tf2::Quaternion rotation = orientation2 * orientation1;
128  tf.rotation = tf2::toMsg(rotation);
129 
130  return tf;
131 }
132 
133 void targets::uuid_callback (const swarmros::String::ConstPtr& msg)
134 {
135  cps = msg->value;
136 }
targets()
Constructor that initializes the private member variables.
Definition: targets.cpp:3
unordered_map< unsigned int, shared_ptr< target > > target_map
A map holding ID and target object of all known targets.
Definition: targets.h:76
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:91
void uuid_callback(const swarmros::String::ConstPtr &msg)
Callback function to receive the UUID from the communication library.
Definition: targets.cpp:133
geometry_msgs::Transform transform(geometry_msgs::Pose p1, geometry_msgs::Pose p2) const
Compute the transformation between two poses.
Definition: targets.cpp:103
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:81
void simulate()
Read simulated targets from parameter file.
Definition: targets.cpp:34
string cps
The UUID of the CPS that owns this class instance.
Definition: targets.h:86
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:57
NodeHandle nh
A node handle for the main ROS node.
Definition: targets.h:66
Publisher tracking_pub
Publisher for transmitting target tracking information.
Definition: targets.h:71
target_state_t
An enumeration for the state of a target.
Definition: target.h:14
geometry_msgs::Pose pose
Current position of the CPS.


target_monitor
Author(s): Micha Sende
autogenerated on Thu Oct 31 2019 15:47:40