37 #include <boost/thread.hpp>
43 #include <sensor_msgs/Image.h>
44 #include <image_cb_detector/ConfigAction.h>
45 #include <calibration_msgs/Interval.h>
57 pub_ = nh_.advertise<calibration_msgs::CalibrationPattern>(
"features",1);
64 boost::mutex::scoped_lock lock(run_mutex_);
71 image_cb_detector::ConfigGoalConstPtr goal = as_.acceptNewGoal();
75 bool success = detector_.configure(*goal);
84 boost::mutex::scoped_lock lock(run_mutex_);
92 boost::mutex::scoped_lock lock(run_mutex_);
96 calibration_msgs::CalibrationPattern features;
98 success = detector_.detect(image, features);
102 ROS_ERROR(
"Error trying to detect checkerboard, not going to publish CalibrationPattern");
106 pub_.publish(features);
122 int main(
int argc,
char** argv)
124 ros::init(argc, argv,
"image_cb_detector_action");