37 #include <boost/thread.hpp>
43 #include <monocam_settler/ConfigAction.h>
44 #include <calibration_msgs/CalibrationPattern.h>
45 #include <calibration_msgs/Interval.h>
58 pub_ = nh_.advertise<calibration_msgs::Interval>(
"settled_interval", 1);
65 boost::mutex::scoped_lock lock(run_mutex_);
72 monocam_settler::ConfigGoalConstPtr goal = as_.acceptNewGoal();
76 bool success = settler_.configure(*goal);
85 boost::mutex::scoped_lock lock(run_mutex_);
89 void msgCallback(
const calibration_msgs::CalibrationPatternConstPtr& msg)
91 boost::mutex::scoped_lock lock(run_mutex_);
97 calibration_msgs::Interval interval;
98 success = settler_.add(msg, interval);
101 pub_.publish(interval);
105 interval.start = msg->header.stamp;
106 interval.end = msg->header.stamp;
107 pub_.publish(interval);
111 ROS_DEBUG(
"Got a feature msg, but not doing anything with it. No active goal, so node is currently idle");
124 int main(
int argc,
char** argv)
126 ros::init(argc, argv,
"joint_states_settler_action");