uav_simple_tracking.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <ros/console.h>
3 #include <actionlib/server/simple_action_server.h>
4 #include <cpswarm_msgs/TrackingAction.h>
5 #include <cpswarm_msgs/TargetPositionEvent.h>
7 
8 using namespace ros;
9 
14 
18 int target;
19 
23 typedef actionlib::SimpleActionServer<cpswarm_msgs::TrackingAction> action_server_t;
24 
30 void ActionCallback(const cpswarm_msgs::TrackingGoalConstPtr& goal, action_server_t* as)
31 {
32  NodeHandle nh;
33 
34  // target id
35  target = goal->target;
36 
37  // set loop rate
38  double loop_rate;
39  nh.param(this_node::getName() + "/loop_rate", loop_rate, 5.0);
40  Rate rate(loop_rate);
41 
42  ROS_INFO("Executing tracking");
43 
44  // tracking library
45  uav_simple_tracking uav_tracking(target);
46 
47  // execute tracking until state changes
49  while (ok() && !as->isPreemptRequested() && state == STATE_ACTIVE) {
50  ROS_DEBUG("Tracking step");
51  behavior_state_t result = uav_tracking.step();
52  if (state == STATE_ACTIVE)
53  state = result;
54  rate.sleep();
55  spinOnce();
56  }
57 
58  // tracking succeeded
59  if (state == STATE_SUCCEEDED) {
60  ROS_INFO("Tracking succeeded");
61  as->setSucceeded();
62  }
63 
64  // tracking aborted
65  else if (state == STATE_ABORTED) {
66  ROS_INFO("Tracking aborted");
67  as->setAborted();
68  }
69 
70  // tracking was preempted
71  else{
72  ROS_INFO("Tracking preempted");
73  as->setPreempted();
74  }
75 }
76 
81 void lost_callback (const cpswarm_msgs::TargetPositionEvent::ConstPtr& msg)
82 {
83  if (msg->id == target)
85 }
86 
91 void done_callback (const cpswarm_msgs::TargetPositionEvent::ConstPtr& msg)
92 {
93  if (msg->id == target)
95 }
96 
103 int main (int argc, char** argv)
104 {
105  // init ros node
106  init(argc, argv, "uav_tracking");
107  NodeHandle nh;
108 
109  // define which log messages are shown
110  if (console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, console::levels::Info)) {
111  console::notifyLoggerLevelsChanged();
112  }
113  else{
114  ROS_ERROR("Could not set logger level!");
115  }
116 
117  // initially, no targets being tracked
118  target = -1;
119 
120  // subscribers
121  int queue_size;
122  nh.param(this_node::getName() + "/queue_size", queue_size, 1);
123  Subscriber lost_sub = nh.subscribe("target_lost", queue_size, lost_callback);
124  Subscriber done_sub = nh.subscribe("target_done", queue_size, done_callback);
125 
126  // start action server
127  action_server_t as(nh, "uav_tracking", boost::bind(&ActionCallback, _1, &as), false);
128  as.start();
129 
130  // wait for action client
131  spin();
132 
133  return 0;
134 }
135 
An implementation that allows to track a target by minimizing the offset between the cyber physical s...
behavior_state_t state
The state of the behavior algorithm.
behavior_state_t step()
Execute one cycle of the tracking algorithm.
void lost_callback(const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
Callback function to receive event that target has been lost.
int main(int argc, char **argv)
Main function to be executed by ROS.
actionlib::SimpleActionServer< cpswarm_msgs::TrackingAction > action_server_t
An action server type that allows to start and stop the tracking task.
int target
The ID of the target being tracked.
void done_callback(const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
Callback function to receive event that target has been done.
behavior_state_t
An enumeration for the state of the behavior algorithm.
void ActionCallback(const cpswarm_msgs::TrackingGoalConstPtr &goal, action_server_t *as)
Callback of the action server which executes the tracking task until it is preempted or finished...


uav_simple_tracking
Author(s): Micha Sende
autogenerated on Sun Dec 29 2019 10:26:16