Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00036 
00037 #include <laser_cb_detector/laser_cb_detector.h>
00038 #include <ros/console.h>
00039 #include <cv_bridge/CvBridge.h>
00040 
00041 
00042 using namespace std;
00043 using namespace laser_cb_detector;
00044 
00045 LaserCbDetector::LaserCbDetector() : configured_(false) {}
00046 
00047 bool LaserCbDetector::configure(const ConfigGoal& config)
00048 {
00049   config_ = config;
00050   image_cb_detector::ConfigGoal image_cfg;
00051   
00052 
00053   image_cfg.num_x = config.num_x;
00054   image_cfg.num_y = config.num_y;
00055   image_cfg.spacing_x = config.spacing_x;
00056   image_cfg.spacing_y = config.spacing_y;
00057 
00058   image_cfg.width_scaling = config.width_scaling;
00059   image_cfg.height_scaling = config.height_scaling;
00060 
00061   image_cfg.subpixel_window = config.subpixel_window;
00062   image_cfg.subpixel_zero_zone = config.subpixel_zero_zone;
00063 
00064   detector_.configure(image_cfg);
00065   return true;
00066 }
00067 
00068 bool LaserCbDetector::detect(const calibration_msgs::DenseLaserSnapshot& snapshot,
00069                              calibration_msgs::CalibrationPattern& result)
00070 {
00071   
00072   if(!bridge_.fromIntensity(snapshot, config_.min_intensity, config_.max_intensity))
00073     return false;
00074   IplImage* image = bridge_.toIpl();
00075 
00076   if (config_.flip_horizontal)
00077   {
00078     ROS_DEBUG("Flipping image");
00079     cvFlip(image, NULL, 1);
00080   }
00081   else
00082     ROS_DEBUG("Not flipping image");
00083 
00084   sensor_msgs::CvBridge cvbridge_;
00085   sensor_msgs::Image::Ptr ros_image = cvbridge_.cvToImgMsg(image);
00086   if(detector_.detect(ros_image, result)){
00087     if (config_.flip_horizontal){
00088       for(int i=0; i < result.image_points.size(); i++)
00089         result.image_points[i].x = image->width - result.image_points[i].x - 1;
00090     }
00091     return true;
00092   }else
00093     return false;
00094 }
00095 
00096 bool LaserCbDetector::getImage(const calibration_msgs::DenseLaserSnapshot& snapshot, sensor_msgs::Image& ros_image)
00097 {
00098   if(!bridge_.fromIntensity(snapshot, config_.min_intensity, config_.max_intensity))
00099   {
00100     ROS_ERROR("Error building IplImage from DenseLaserSnapshot's intensity data");
00101     return false;
00102   }
00103   IplImage* image = bridge_.toIpl();
00104 
00105   if(!sensor_msgs::CvBridge::fromIpltoRosImage(image, ros_image, "mono8"))
00106   {
00107     ROS_ERROR("Error converting IplImage to a ROS sensor_msgs::Image");
00108     return false;
00109   }
00110 
00111   return true;
00112 }
00113