7 nh.param(this_node::getName() +
"/loop_rate", loop_rate, 5.0);
10 nh.param(this_node::getName() +
"/queue_size", queue_size, 10);
11 nh.param(this_node::getName() +
"/fov",
fov, 0.5);
18 nh.getParam(this_node::getNamespace() +
"/targets_done", done);
20 target_map.emplace(piecewise_construct, forward_as_tuple(t), forward_as_tuple(make_shared<target>(t,
TARGET_DONE)));
24 tracking_pub =
nh.advertise<cpswarm_msgs::TargetTracking>(
"target_tracking", queue_size,
true);
28 while (ok() &&
cps ==
"") {
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...");
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;
68 geometry_msgs::Pose t_pose = t.second->get_pose();
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);
73 if (hypot(pose.position.x - t_pose.position.x, pose.position.y - t_pose.position.y) <=
fov) {
75 cpswarm_msgs::TargetTracking track;
76 track.header.stamp = Time::now();
87 geometry_msgs::Pose
pose;
90 ROS_DEBUG(
"Target %d at [%.2f, %.2f]", msg.id, pose.position.x, pose.position.y);
94 target_map[msg.id]->update(state, pose, msg.header.stamp);
99 target_map.emplace(piecewise_construct, forward_as_tuple(msg.id), forward_as_tuple(make_shared<target>(msg.id, state, pose, msg.header.stamp)));
106 tf2::Quaternion orientation1;
107 tf2::fromMsg(p1.orientation, orientation1);
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);
116 geometry_msgs::Transform tf;
119 tf.translation.x = -distance * cos(direction);
120 tf.translation.y = distance * sin(direction);
123 p1.orientation.w *= -1;
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);
targets()
Constructor that initializes the private member variables.
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.
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 tracking_pub
Publisher for transmitting target tracking information.
target_state_t
An enumeration for the state of a target.
geometry_msgs::Pose pose
Current position of the CPS.