47 #define ROS_INFO_CONFIG(name) \
50 ss << "[" << #name << "] -> " << config.name;\
51 ROS_INFO("%s", ss.str().c_str());\
56 laser_cb_detector::ConfigGoal config;
61 pn.
param(
"num_x", num_x, 3);
62 config.num_x = (
unsigned int) num_x;
65 pn.
param(
"num_y", num_y, 3);
66 config.num_y = (
unsigned int) num_y;
69 pn.
param(
"spacing_x", spacing_x, 1.0);
70 config.spacing_x = spacing_x;
73 pn.
param(
"spacing_y", spacing_y, 1.0);
74 config.spacing_y = spacing_y;
77 pn.
param(
"width_scaling", width_scaling, 1.0);
78 config.width_scaling = width_scaling;
80 double height_scaling;
81 pn.
param(
"height_scaling", height_scaling, 1.0);
82 config.height_scaling = height_scaling;
85 pn.
param(
"min_intensity", min_intensity, 500.0);
86 config.min_intensity = min_intensity;
89 pn.
param(
"max_intensity", max_intensity, 5000.0);
90 config.max_intensity = max_intensity;
93 pn.
param(
"subpixel_window", subpixel_window, 2);
94 config.subpixel_window = subpixel_window;
96 pn.
param(
"subpixel_zero_zone", config.subpixel_zero_zone, -1);
99 pn.
param(
"flip_horizontal", flip_horizontal, 0);
101 config.flip_horizontal = 1;
103 config.flip_horizontal = 0;
116 ROS_INFO(
"[flip_horizontal]->%u", config.flip_horizontal);
126 detector_.configure(config);
133 pub_ = nh_.advertise<calibration_msgs::CalibrationPattern>(
"laser_checkerboard", 1);
135 image_pub_ = nh_.advertise<sensor_msgs::Image>(
"image", 1);
145 boost::mutex::scoped_lock lock(run_mutex_);
151 laser_cb_detector::ConfigGoalConstPtr goal = as_.acceptNewGoal();
153 bool success = detector_.configure(*goal);
161 boost::mutex::scoped_lock lock(run_mutex_);
168 boost::mutex::scoped_lock lock(run_mutex_);
171 calibration_msgs::CalibrationPattern result;
172 detect_result = detector_.detect(*msg, result);
175 ROS_ERROR(
"Error during checkerboard detection. (This error is worse than simply not seeing a checkerboard");
178 result.header.stamp = msg->header.stamp;
179 pub_.publish(result);
182 sensor_msgs::Image image;
183 if(detector_.getImage(*msg, image))
185 image.header.stamp = msg->header.stamp;
186 image_pub_.publish(image);
189 ROS_ERROR(
"Error trying to generate ROS image");
203 int main(
int argc,
char** argv)
205 ros::init(argc, argv,
"laser_cb_detector");