37 #include <boost/scoped_ptr.hpp>    43 #include <calibration_msgs/Interval.h>    44 #include <calibration_msgs/IntervalStatus.h>    45 #include <interval_intersection/ConfigAction.h>    57     pub_ = nh_.advertise<calibration_msgs::Interval>(
"intersected_interval", 1);
    58     status_pub_ = nh_.advertise<calibration_msgs::IntervalStatus>(
    59           "intersected_interval_status", 1);
    65     ROS_DEBUG(
"Start interval intersection with no input topics");
    71     boost::mutex::scoped_lock lock(run_mutex_);
    81     interval_intersection::ConfigGoalConstPtr goal = as_.acceptNewGoal();
    88     subscribers_.resize(goal->topics.size());
    89     topics_.resize(goal->topics.size());
    90     for (
unsigned int i=0; i<goal->topics.size(); i++)
    92       ROS_DEBUG(
"Subscribing to: %s", goal->topics[i].c_str());
    93       subscribers_[i] = intersect_nh_->subscribe<calibration_msgs::Interval>(goal->topics[i], 200, intersect_->getNewInputStream());
    94       topics_[i] = goal->topics[i];
   100     boost::mutex::scoped_lock lock(run_mutex_);
   108     assert(intersect_nh_);
   111     ROS_DEBUG(
"Shutting Down IntervalIntersection");
   112     intersect_nh_->shutdown();
   114     subscribers_.clear();
   116     intersect_nh_.reset();
   122     pub_.publish(interval);
   126      ROS_DEBUG(
"Publishing interval intersection status");
   129         calibration_msgs::IntervalStatus status = intersect_->get_status();
   133         for ( 
size_t i=0; i<status.yeild_rates.size(); ++i ) {
   134            status.names[i] = topics_[i];
   135            ROS_DEBUG(
"Topic %s has a success rate of %f", 
   136                  status.names[i].c_str(), status.yeild_rates[i]);
   139         status_pub_.publish(status);
   158 int main(
int argc, 
char** argv)
   160   ros::init(argc, argv, 
"intersection_action_node");
 
vector< std::string > topics_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
boost::scoped_ptr< IntervalIntersector > intersect_
actionlib::SimpleActionServer< interval_intersection::ConfigAction > as_
boost::scoped_ptr< ros::NodeHandle > intersect_nh_
IntervalIntersectionAction()
ros::Publisher status_pub_
void publishResult(calibration_msgs::Interval interval)
vector< ros::Subscriber > subscribers_