45 LaserCbDetector::LaserCbDetector() : configured_(false) {}
50 image_cb_detector::ConfigGoal image_cfg;
53 image_cfg.num_x = config.num_x;
54 image_cfg.num_y = config.num_y;
55 image_cfg.spacing_x = config.spacing_x;
56 image_cfg.spacing_y = config.spacing_y;
58 image_cfg.width_scaling = config.width_scaling;
59 image_cfg.height_scaling = config.height_scaling;
61 image_cfg.subpixel_window = config.subpixel_window;
62 image_cfg.subpixel_zero_zone = config.subpixel_zero_zone;
69 calibration_msgs::CalibrationPattern& result)
79 cv::flip(image, image, 1);
85 sensor_msgs::ImagePtr ros_image = cv_image.
toImageMsg();
88 for(
int i=0; i < result.image_points.size(); i++)
89 result.image_points[i].x = image.cols - result.image_points[i].x - 1;
100 ROS_ERROR(
"Error building cv::Mat from DenseLaserSnapshot's intensity data");
bool detect(const calibration_msgs::DenseLaserSnapshot &snapshot, calibration_msgs::CalibrationPattern &result)
bool fromIntensity(const calibration_msgs::DenseLaserSnapshot &snapshot, float min_val, float max_val)
bool detect(const sensor_msgs::ImageConstPtr &image, calibration_msgs::CalibrationPattern &result)
bool getImage(const calibration_msgs::DenseLaserSnapshot &snapshot, sensor_msgs::Image &ros_image)
bool configure(const ConfigGoal &config)
image_cb_detector::ImageCbDetector detector_
sensor_msgs::ImagePtr toImageMsg() const
bool configure(const ConfigGoal &config)