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> 23 typedef actionlib::SimpleActionServer<cpswarm_msgs::TrackingAction>
action_server_t;
39 nh.param(this_node::getName() +
"/loop_rate", loop_rate, 5.0);
42 ROS_INFO(
"Executing tracking");
49 while (ok() && !as->isPreemptRequested() && state ==
STATE_ACTIVE) {
50 ROS_DEBUG(
"Tracking step");
60 ROS_INFO(
"Tracking succeeded");
66 ROS_INFO(
"Tracking aborted");
72 ROS_INFO(
"Tracking preempted");
81 void lost_callback (
const cpswarm_msgs::TargetPositionEvent::ConstPtr& msg)
91 void done_callback (
const cpswarm_msgs::TargetPositionEvent::ConstPtr& msg)
103 int main (
int argc,
char** argv)
106 init(argc, argv,
"uav_tracking");
110 if (console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, console::levels::Info)) {
111 console::notifyLoggerLevelsChanged();
114 ROS_ERROR(
"Could not set logger level!");
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);
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...