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
00036
00037 #include <boost/thread.hpp>
00038 #include <ros/ros.h>
00039 #include <actionlib/server/simple_action_server.h>
00040
00041 #include <joint_states_settler/joint_states_settler.h>
00042 #include <joint_states_settler/ConfigAction.h>
00043 #include <calibration_msgs/Interval.h>
00044 #include <sensor_msgs/JointState.h>
00045
00046 using namespace joint_states_settler;
00047
00048 class JointStatesSettlerAction
00049 {
00050 public:
00051 JointStatesSettlerAction() : as_("settler_config", false)
00052 {
00053 as_.registerGoalCallback( boost::bind(&JointStatesSettlerAction::goalCallback, this) );
00054 as_.registerPreemptCallback( boost::bind(&JointStatesSettlerAction::preemptCallback, this) );
00055 interval_pub_ = nh_.advertise<calibration_msgs::Interval>("settled_interval", 1);
00056 pruned_pub_ = nh_.advertise<sensor_msgs::JointState>("chain_state", 1);
00057 sub_ = nh_.subscribe("joint_states", 1, &JointStatesSettlerAction::jointStatesCallback, this);
00058 as_.start();
00059 }
00060
00061 void goalCallback()
00062 {
00063 boost::mutex::scoped_lock lock(run_mutex_);
00064
00065
00066 if (as_.isActive())
00067 as_.setPreempted();
00068
00069
00070 joint_states_settler::ConfigGoalConstPtr goal = as_.acceptNewGoal();
00071 assert(goal);
00072
00073
00074 bool success = settler_.configure(*goal);
00075
00076
00077 if (!success)
00078 as_.setAborted();
00079 }
00080
00081 void preemptCallback()
00082 {
00083 boost::mutex::scoped_lock lock(run_mutex_);
00084
00085
00086 as_.setPreempted();
00087 }
00088
00089 void jointStatesCallback(const sensor_msgs::JointStateConstPtr& msg)
00090 {
00091 boost::mutex::scoped_lock lock(run_mutex_);
00092
00093
00094 if (!as_.isActive())
00095 return;
00096
00097
00098 calibration_msgs::Interval interval = settler_.add(msg);
00099 interval_pub_.publish(interval);
00100
00101
00102 pruned_pub_.publish(settler_.pruneJointState(msg));
00103 }
00104
00105 private:
00106 boost::mutex run_mutex_;
00107 actionlib::SimpleActionServer<joint_states_settler::ConfigAction> as_;
00108 JointStatesSettler settler_;
00109
00110 ros::Publisher interval_pub_;
00111 ros::Publisher pruned_pub_;
00112 ros::Subscriber sub_;
00113 ros::NodeHandle nh_;
00114 };
00115
00116 int main(int argc, char** argv)
00117 {
00118 ros::init(argc, argv, "joint_states_settler_action");
00119 ros::NodeHandle n;
00120 JointStatesSettlerAction settler_action;
00121 ros::spin();
00122 return 0;
00123 }