$search
00001 /********************************************************************** 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2009, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Willow Garage nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 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 <interval_intersection/ConfigAction.h> 00045 00046 using namespace std; 00047 using namespace interval_intersection; 00048 00049 class IntervalIntersectionAction 00050 { 00051 public: 00052 IntervalIntersectionAction() : as_("interval_intersection_config", false) 00053 { 00054 as_.registerGoalCallback( boost::bind(&IntervalIntersectionAction::goalCallback, this) ); 00055 as_.registerPreemptCallback( boost::bind(&IntervalIntersectionAction::preemptCallback, this) ); 00056 pub_ = nh_.advertise<calibration_msgs::Interval>("interval", 1); 00057 00058 ROS_DEBUG("Start interval intersection with no input topics"); 00059 as_.start(); 00060 } 00061 00062 void goalCallback() 00063 { 00064 boost::mutex::scoped_lock lock(run_mutex_); 00065 00066 // Stop currently running goal, if there's a goal running 00067 if (as_.isActive()) 00068 { 00069 tearDown(); 00070 as_.setPreempted(); 00071 } 00072 00073 // Get the new goal from the action server 00074 interval_intersection::ConfigGoalConstPtr goal = as_.acceptNewGoal(); 00075 assert(goal); 00076 00077 // Reconfigure the node 00078 intersect_nh_.reset(new ros::NodeHandle); 00079 intersect_.reset(new IntervalIntersector( boost::bind(&IntervalIntersectionAction::publishResult, this, _1))); 00080 // Subscribe to all the requested topics 00081 subscribers_.resize(goal->topics.size()); 00082 for (unsigned int i=0; i<goal->topics.size(); i++) 00083 { 00084 ROS_DEBUG("Subscribing to: %s", goal->topics[i].c_str()); 00085 subscribers_[i] = intersect_nh_->subscribe<calibration_msgs::Interval>(goal->topics[i], 200, intersect_->getNewInputStream()); 00086 } 00087 } 00088 00089 void preemptCallback() 00090 { 00091 boost::mutex::scoped_lock lock(run_mutex_); 00092 tearDown(); 00093 as_.setPreempted(); 00094 } 00095 00096 void tearDown() 00097 { 00098 assert(intersect_); 00099 assert(intersect_nh_); 00100 00101 // Shutdown the subnode, to ensure that none of the callbacks are called 00102 ROS_DEBUG("Shutting Down IntervalIntersection"); 00103 intersect_nh_->shutdown(); 00104 00105 subscribers_.clear(); 00106 intersect_.reset(); 00107 intersect_nh_.reset(); 00108 } 00109 00110 void publishResult(calibration_msgs::Interval interval) 00111 { 00112 ROS_DEBUG("Publishing"); 00113 pub_.publish(interval); 00114 } 00115 00116 private: 00117 boost::mutex run_mutex_; 00118 actionlib::SimpleActionServer<interval_intersection::ConfigAction> as_; 00119 00120 boost::scoped_ptr<ros::NodeHandle> intersect_nh_; 00121 boost::scoped_ptr<IntervalIntersector> intersect_; 00122 vector<ros::Subscriber> subscribers_; 00123 00124 ros::Publisher pub_; 00125 ros::NodeHandle nh_; 00126 }; 00127 00128 int main(int argc, char** argv) 00129 { 00130 ros::init(argc, argv, "intersection_action_node"); 00131 00132 ros::NodeHandle n; 00133 00134 IntervalIntersectionAction intersect_action; 00135 00136 ros::spin(); 00137 00138 return 0; 00139 }