Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <vector>
00037 #include <boost/scoped_ptr.hpp>
00038 #include <ros/ros.h>
00039 #include <ros/console.h>
00040 #include <actionlib/server/simple_action_server.h>
00041 #include <interval_intersection/interval_intersection.hpp>
00042
00043 #include <calibration_msgs/Interval.h>
00044 #include <calibration_msgs/IntervalStatus.h>
00045 #include <interval_intersection/ConfigAction.h>
00046
00047 using namespace std;
00048 using namespace interval_intersection;
00049
00050 class IntervalIntersectionAction
00051 {
00052 public:
00053 IntervalIntersectionAction() : as_("interval_intersection_config", false)
00054 {
00055 as_.registerGoalCallback( boost::bind(&IntervalIntersectionAction::goalCallback, this) );
00056 as_.registerPreemptCallback( boost::bind(&IntervalIntersectionAction::preemptCallback, this) );
00057 pub_ = nh_.advertise<calibration_msgs::Interval>("intersected_interval", 1);
00058 status_pub_ = nh_.advertise<calibration_msgs::IntervalStatus>(
00059 "intersected_interval_status", 1);
00060
00061
00062 status_timer_ = nh_.createTimer(ros::Duration(1.0),
00063 boost::bind(&IntervalIntersectionAction::publishStatus, this));
00064
00065 ROS_DEBUG("Start interval intersection with no input topics");
00066 as_.start();
00067 }
00068
00069 void goalCallback()
00070 {
00071 boost::mutex::scoped_lock lock(run_mutex_);
00072
00073
00074 if (as_.isActive())
00075 {
00076 tearDown();
00077 as_.setPreempted();
00078 }
00079
00080
00081 interval_intersection::ConfigGoalConstPtr goal = as_.acceptNewGoal();
00082 assert(goal);
00083
00084
00085 intersect_nh_.reset(new ros::NodeHandle);
00086 intersect_.reset(new IntervalIntersector( boost::bind(&IntervalIntersectionAction::publishResult, this, _1)));
00087
00088 subscribers_.resize(goal->topics.size());
00089 topics_.resize(goal->topics.size());
00090 for (unsigned int i=0; i<goal->topics.size(); i++)
00091 {
00092 ROS_DEBUG("Subscribing to: %s", goal->topics[i].c_str());
00093 subscribers_[i] = intersect_nh_->subscribe<calibration_msgs::Interval>(goal->topics[i], 200, intersect_->getNewInputStream());
00094 topics_[i] = goal->topics[i];
00095 }
00096 }
00097
00098 void preemptCallback()
00099 {
00100 boost::mutex::scoped_lock lock(run_mutex_);
00101 tearDown();
00102 as_.setPreempted();
00103 }
00104
00105 void tearDown()
00106 {
00107 assert(intersect_);
00108 assert(intersect_nh_);
00109
00110
00111 ROS_DEBUG("Shutting Down IntervalIntersection");
00112 intersect_nh_->shutdown();
00113
00114 subscribers_.clear();
00115 intersect_.reset();
00116 intersect_nh_.reset();
00117 }
00118
00119 void publishResult(calibration_msgs::Interval interval)
00120 {
00121 ROS_DEBUG("Publishing");
00122 pub_.publish(interval);
00123 }
00124
00125 void publishStatus() {
00126 ROS_DEBUG("Publishing interval intersection status");
00127 if ( intersect_ ) {
00128
00129 calibration_msgs::IntervalStatus status = intersect_->get_status();
00130
00131 status.header.stamp = ros::Time::now();
00132
00133 for ( size_t i=0; i<status.yeild_rates.size(); ++i ) {
00134 status.names[i] = topics_[i];
00135 ROS_DEBUG("Topic %s has a success rate of %f",
00136 status.names[i].c_str(), status.yeild_rates[i]);
00137 }
00138
00139 status_pub_.publish(status);
00140 }
00141 }
00142
00143 private:
00144 boost::mutex run_mutex_;
00145 actionlib::SimpleActionServer<interval_intersection::ConfigAction> as_;
00146
00147 boost::scoped_ptr<ros::NodeHandle> intersect_nh_;
00148 boost::scoped_ptr<IntervalIntersector> intersect_;
00149 vector<ros::Subscriber> subscribers_;
00150 vector<std::string> topics_;
00151
00152 ros::Publisher pub_;
00153 ros::Publisher status_pub_;
00154 ros::NodeHandle nh_;
00155 ros::Timer status_timer_;
00156 };
00157
00158 int main(int argc, char** argv)
00159 {
00160 ros::init(argc, argv, "intersection_action_node");
00161 IntervalIntersectionAction intersect_action;
00162 ros::spin();
00163 return 0;
00164 }