37 #include <boost/thread.hpp> 42 #include <joint_states_settler/ConfigAction.h> 43 #include <calibration_msgs/Interval.h> 44 #include <sensor_msgs/JointState.h> 55 interval_pub_ = nh_.advertise<calibration_msgs::Interval>(
"settled_interval", 1);
56 pruned_pub_ = nh_.advertise<sensor_msgs::JointState>(
"chain_state", 1);
63 boost::mutex::scoped_lock lock(run_mutex_);
70 joint_states_settler::ConfigGoalConstPtr goal = as_.acceptNewGoal();
74 bool success = settler_.configure(*goal);
83 boost::mutex::scoped_lock lock(run_mutex_);
91 boost::mutex::scoped_lock lock(run_mutex_);
98 calibration_msgs::Interval interval = settler_.add(msg);
99 interval_pub_.publish(interval);
102 pruned_pub_.publish(settler_.pruneJointState(msg));
116 int main(
int argc,
char** argv)
118 ros::init(argc, argv,
"joint_states_settler_action");
JointStatesSettlerAction()
void jointStatesCallback(const sensor_msgs::JointStateConstPtr &msg)
ros::Publisher pruned_pub_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher interval_pub_
JointStatesSettler settler_
int main(int argc, char **argv)
actionlib::SimpleActionServer< joint_states_settler::ConfigAction > as_