3 #include <actionlib/server/simple_action_server.h> 4 #include <geometry_msgs/Pose.h> 5 #include <cpswarm_msgs/TaskAllocatedEvent.h> 6 #include <cpswarm_msgs/TargetPositionEvent.h> 7 #include <cpswarm_msgs/TargetTracking.h> 8 #include <cpswarm_msgs/TargetAction.h> 17 typedef actionlib::SimpleActionServer<cpswarm_msgs::TargetAction>
action_server_t;
40 tf2::Quaternion orientation;
41 tf2::fromMsg(
pose.orientation, orientation);
42 return tf2::getYaw(orientation);
49 geometry_msgs::Quaternion
rotate (geometry_msgs::Quaternion rotation)
51 tf2::Quaternion cps_orientation;
52 tf2::fromMsg(
pose.orientation, cps_orientation);
53 tf2::Quaternion target_rotation;
54 tf2::fromMsg(rotation, target_rotation);
55 tf2::Quaternion target_orientation = target_rotation * cps_orientation;
56 target_orientation.normalize();
57 return tf2::toMsg(target_orientation);
67 double distance = hypot(msg->tf.translation.x, msg->tf.translation.y);
68 double direction =
yaw() + atan2(msg->tf.translation.y, -msg->tf.translation.x) - M_PI / 2;
71 cpswarm_msgs::TargetPositionEvent event;
73 event.pose.pose.position.x =
pose.position.x + distance * cos(direction);
74 event.pose.pose.position.y =
pose.position.y + distance * sin(direction);
75 event.pose.pose.orientation =
rotate(msg->tf.rotation);
76 event.header.stamp = msg->header.stamp;
105 cpswarm_msgs::TargetPositionEvent event;
106 event.id = msg->task_id;
107 event.header.stamp = msg->header.stamp;
136 if (msg->header.stamp.isValid())
142 ROS_DEBUG_THROTTLE(1,
"Yaw %.2f",
yaw());
143 ROS_DEBUG_THROTTLE(1,
"Pose [%.2f, %.2f, %.2f]",
pose.position.x,
pose.position.y,
pose.position.z);
154 cpswarm_msgs::TargetPositionEvent event;
156 event.pose = goal->pose;
157 event.header = goal->pose.header;
172 int main (
int argc,
char** argv)
175 init(argc, argv,
"target_monitor");
180 nh.param(this_node::getName() +
"/simulation", simulation,
false);
182 nh.param(this_node::getName() +
"/queue_size", queue_size, 10);
186 nh.param(this_node::getName() +
"/loop_rate", loop_rate, 5.0);
187 Rate rate(loop_rate);
201 Subscriber pose_sub = nh.subscribe(
"pos_provider/pose", queue_size,
pose_callback);
202 Subscriber tracking_sub = nh.subscribe(
"target_tracking", queue_size,
tracking_callback);
203 Subscriber local_assigned_sub = nh.subscribe(
"cps_selected", queue_size,
assigned_callback);
204 Subscriber local_done_sub = nh.subscribe(
"target_done", queue_size,
done_callback);
205 Subscriber found_sub = nh.subscribe(
"bridge/events/target_found", queue_size,
found_callback);
206 Subscriber update_sub = nh.subscribe(
"bridge/events/target_update", queue_size,
update_callback);
207 Subscriber assigned_sub = nh.subscribe(
"bridge/events/cps_selected", queue_size,
assigned_callback);
208 Subscriber lost_sub = nh.subscribe(
"bridge/events/target_lost", queue_size,
lost_callback);
209 Subscriber done_sub = nh.subscribe(
"bridge/events/target_done", queue_size,
done_callback);
217 ROS_DEBUG_ONCE(
"Waiting for valid pose...");
void found_callback(const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
Callback function to receive information about targets found by other CPSs.
targets * monitor
The targets being monitored.
void lost_callback(const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
Callback function to receive information about targets lost by other CPSs.
int main(int argc, char **argv)
Main function to be executed by ROS.
void simulate()
Read simulated targets from parameter file.
void update_callback(const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
Callback function to receive updated information about targets from other CPSs.
void assigned_callback(const cpswarm_msgs::TaskAllocatedEvent::ConstPtr &msg)
Callback function to receive information about targets assigned to a CPSs.
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...
double yaw()
Compute the current yaw orientation of the CPS.
void tracking_callback(const cpswarm_msgs::TargetTracking::ConstPtr &msg)
Callback function for target position.
void set_done(const cpswarm_msgs::TargetGoalConstPtr &goal, action_server_t *as)
Callback of the action server which sets the target state to done.
void done_callback(const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
Callback function for incoming target done events.
geometry_msgs::Quaternion rotate(geometry_msgs::Quaternion rotation)
Compute the orientation resulting from the rotated CPS orientation.
void pose_callback(const geometry_msgs::PoseStamped::ConstPtr &msg)
Callback function for position updates.
A collection of target objects that are searched, tracked, and rescued by the CPSs.
bool pose_valid
Whether a valid position has been received.
geometry_msgs::Pose pose
Current position of the CPS.
actionlib::SimpleActionServer< cpswarm_msgs::TargetAction > action_server_t
An action server type that allows to set the state of a target.