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 
00036 
00037 #include <boost/thread.hpp>
00038 #include <ros/ros.h>
00039 #include <actionlib/server/simple_action_server.h>
00040 #include <monocam_settler/monocam_settler.h>
00041 
00042 
00043 #include <monocam_settler/ConfigAction.h>
00044 #include <calibration_msgs/CalibrationPattern.h>
00045 #include <calibration_msgs/Interval.h>
00046 
00047 using namespace monocam_settler;
00048 
00049 class MonocamSettlerAction
00050 {
00051 public:
00052   MonocamSettlerAction() : as_("monocam_settler_config", false)
00053   {
00054     
00055     as_.registerGoalCallback( boost::bind(&MonocamSettlerAction::goalCallback, this) );
00056     as_.registerPreemptCallback( boost::bind(&MonocamSettlerAction::preemptCallback, this) );
00057 
00058     pub_ = nh_.advertise<calibration_msgs::Interval>("settled_interval", 1);
00059     sub_ = nh_.subscribe("features", 1, &MonocamSettlerAction::msgCallback, this);
00060     as_.start();
00061   }
00062 
00063   void goalCallback()
00064   {
00065     boost::mutex::scoped_lock lock(run_mutex_);
00066 
00067     
00068     if (as_.isActive())
00069       as_.setPreempted();
00070 
00071     
00072     monocam_settler::ConfigGoalConstPtr goal = as_.acceptNewGoal();
00073     assert(goal);
00074 
00075     
00076     bool success = settler_.configure(*goal);
00077 
00078     
00079     if (!success)
00080       as_.setAborted();
00081   }
00082 
00083   void preemptCallback()
00084   {
00085     boost::mutex::scoped_lock lock(run_mutex_);
00086     as_.setPreempted();
00087   }
00088 
00089   void msgCallback(const calibration_msgs::CalibrationPatternConstPtr& msg)
00090   {
00091     boost::mutex::scoped_lock lock(run_mutex_);
00092 
00093     if (as_.isActive())
00094     {
00095       bool success;
00096 
00097       calibration_msgs::Interval interval;
00098       success = settler_.add(msg, interval);
00099 
00100 
00101       if (success)
00102         pub_.publish(interval);
00103       else
00104       {
00105         
00106         interval.start = msg->header.stamp;
00107         interval.end =   msg->header.stamp;
00108         pub_.publish(interval);
00109       }
00110     }
00111     else
00112       ROS_DEBUG("Got a feature msg, but not doing anything with it. No active goal, so node is currently idle");
00113   }
00114 
00115 private:
00116   ros::NodeHandle nh_;
00117   actionlib::SimpleActionServer<monocam_settler::ConfigAction> as_;
00118   ros::Publisher pub_;
00119   ros::Subscriber sub_;
00120 
00121   boost::mutex run_mutex_;
00122   MonocamSettler settler_;
00123 };
00124 
00125 int main(int argc, char** argv)
00126 {
00127   ros::init(argc, argv, "joint_states_settler_action");
00128 
00129   ros::NodeHandle n;
00130 
00131   MonocamSettlerAction settler_action;
00132 
00133   ros::spin();
00134 
00135   return 0;
00136 }
00137