00001 
00018 #include <asr_halcon_bridge/halcon_image.h>
00019 #include <sensor_msgs/image_encodings.h>
00020 #include <boost/make_shared.hpp>
00021 
00022 namespace halcon_bridge {
00023 
00024     const char* INVALID = "invalid";
00025     const char* RGB = "rgb";
00026     const char* BGR = "bgr";
00027 
00028     int getHalconTypeSize(const std::string& type) {
00029 
00030         if ((type == "byte") || (type == "int1")) return 1;
00031         if ((type == "uint2") || (type == "int2")) return 2;
00032         if ((type == "int4") || (type == "real")) return 4;
00033         if (type == "int8") return 8;
00034 
00035         return -1;
00036     }
00037 
00038     const char* getHalconEncoding(const std::string& encoding) {
00039       
00040       if (encoding == sensor_msgs::image_encodings::BGR8)   return "bgr";
00041       if (encoding == sensor_msgs::image_encodings::RGB8)   return "rgb";
00042       if (encoding == sensor_msgs::image_encodings::BGRA8)  return "bgrx";
00043       if (encoding == sensor_msgs::image_encodings::RGBA8)  return "rgbx";
00044 
00045       
00046       if (encoding == sensor_msgs::image_encodings::MONO8)  return "mono";
00047 
00048       
00049       return INVALID;
00050     }
00051 
00052 
00053 
00054     const char* getHalconChannelLength(const std::string& encoding) {
00055 
00056         if ((encoding == sensor_msgs::image_encodings::BGR8) || (encoding == sensor_msgs::image_encodings::RGB8) ||
00057                 (encoding == sensor_msgs::image_encodings::BGRA8) || (encoding == sensor_msgs::image_encodings::RGBA8) ||
00058                 (encoding == sensor_msgs::image_encodings::MONO8)) {
00059           return "byte";
00060         }
00061       if ((encoding == sensor_msgs::image_encodings::BGR16) || (encoding == sensor_msgs::image_encodings::RGB16) ||
00062               (encoding == sensor_msgs::image_encodings::BGRA16) || (encoding == sensor_msgs::image_encodings::RGBA16) ||
00063               (encoding == sensor_msgs::image_encodings::MONO16)) {
00064          return "uint2";
00065       }
00066 
00067       return INVALID;
00068     }
00069 
00070 
00071 
00072     const char* getColorChannelOrder(const std::string& encoding) {
00073         if ((encoding == sensor_msgs::image_encodings::BGR8) || (encoding == sensor_msgs::image_encodings::BGRA8) ||
00074                 (encoding == sensor_msgs::image_encodings::BGR16) || (encoding == sensor_msgs::image_encodings::BGRA16)) {
00075             return BGR;
00076         }
00077         if ((encoding == sensor_msgs::image_encodings::RGB8) || (encoding == sensor_msgs::image_encodings::RGBA8) ||
00078                 (encoding == sensor_msgs::image_encodings::RGB16) || (encoding == sensor_msgs::image_encodings::RGBA16)) {
00079             return RGB;
00080         }
00081         return INVALID;
00082     }
00083 
00084 
00085 
00086 
00087     HalconImage::~HalconImage() {
00088         delete image;
00089     }
00090 
00091     sensor_msgs::ImagePtr HalconImage::toImageMsg() const {
00092       sensor_msgs::ImagePtr ptr = boost::make_shared<sensor_msgs::Image>();
00093       toImageMsg(*ptr);
00094       return ptr;
00095     }
00096 
00097 
00098 
00099     void HalconImage::toImageMsg(sensor_msgs::Image& ros_image) const {
00100         long width, height;
00101         width = image->Width();
00102         height = image->Height();
00103 
00104         int channel_count = image->CountChannels();
00105 
00106         ros_image.height = height;
00107         ros_image.width = width;
00108         ros_image.encoding = encoding;
00109         ros_image.is_bigendian = false;
00110         ros_image.step = channel_count * width;
00111 
00112 
00113         HalconCpp::HString typeReturn;
00114         Hlong widthReturn;
00115         Hlong heightReturn;
00116         HalconCpp::HString type = image->GetImageType();
00117 
00118         if (channel_count > 1) {
00119 
00120             
00121 
00122             HalconCpp::HImage *interleavedImage = new HalconCpp::HImage(type, width * 3, height);
00123 
00124             HalconCpp::HHomMat2D homMat;
00125             homMat = homMat.HomMat2dScale(1, 3, 0, 0);
00126 
00127             HalconCpp::HImage transImage = image->AffineTransImageSize(homMat, "constant", width * 3, height);
00128 
00129             HalconCpp::HImage imageRed;
00130             HalconCpp::HImage imageGreen;
00131             HalconCpp::HImage imageBlue;
00132             imageRed = transImage.Decompose3(&imageGreen, &imageBlue);
00133 
00134 
00135             HalconCpp::HRegion regionGrid;
00136             regionGrid.GenGridRegion(2 * height, 3, "lines", width * 3, height + 1);
00137             HalconCpp::HRegion movedRegion = regionGrid.MoveRegion(-1, 0);
00138             HalconCpp::HRegion clippedRegion = movedRegion.ClipRegion(0, 0, height - 1, (3 * width) - 1);
00139 
00140             if (getColorChannelOrder(encoding) == RGB) {
00141                 imageRed = imageRed.ReduceDomain(clippedRegion);
00142             } else {
00143                 imageBlue = imageBlue.ReduceDomain(clippedRegion);
00144             }
00145             movedRegion = regionGrid.MoveRegion(-1, 1);
00146             clippedRegion = movedRegion.ClipRegion(0, 0, height - 1, (3 * width) - 1);
00147             imageGreen = imageGreen.ReduceDomain(clippedRegion);
00148             movedRegion = regionGrid.MoveRegion(-1, 2);
00149             clippedRegion = movedRegion.ClipRegion(0, 0, height - 1, (3 * width) - 1);
00150             if (getColorChannelOrder(encoding) == RGB) {
00151                 imageBlue = imageBlue.ReduceDomain(clippedRegion);
00152             } else {
00153                 imageRed = imageRed.ReduceDomain(clippedRegion);
00154             }
00155 
00156             interleavedImage->OverpaintGray(imageRed);
00157             interleavedImage->OverpaintGray(imageGreen);
00158             interleavedImage->OverpaintGray(imageBlue);
00159 
00160 
00161 
00162             
00163             unsigned char* colorData = (unsigned char*)interleavedImage->GetImagePointer1(&typeReturn, &widthReturn, &heightReturn);
00164             int interleavedHeight = interleavedImage->Height();
00165             int interleavedWidth =  interleavedImage->Width();
00166             size_t size = interleavedHeight * interleavedWidth * getHalconTypeSize((std::string)typeReturn);
00167             ros_image.data.resize(size);
00168             memcpy((unsigned char*)(&ros_image.data[0]), colorData, size);
00169 
00170             interleavedImage->Clear();
00171             imageRed.Clear();
00172             imageGreen.Clear();
00173             imageBlue.Clear();
00174             homMat.Clear();
00175             regionGrid.Clear();
00176             clippedRegion.Clear();
00177             movedRegion.Clear();
00178 
00179 
00180         } else {
00181 
00182             
00183             unsigned char* colorData = (unsigned char*)image->GetImagePointer1(&typeReturn, &widthReturn, &heightReturn);
00184             size_t size = height * width * getHalconTypeSize((std::string)typeReturn);
00185             ros_image.data.resize(size);
00186             memcpy((unsigned char*)(&ros_image.data[0]), colorData, size);
00187         }
00188 
00189     }
00190 
00191 
00192 
00193     HalconImagePtr toHalconCopy(const sensor_msgs::ImageConstPtr& source) {
00194       return toHalconCopy(*source);
00195     }
00196 
00197     HalconImagePtr toHalconCopy(const sensor_msgs::Image& source) {
00198         HalconImagePtr ptr = boost::make_shared<HalconImage>();
00199         ptr->header = source.header;
00200         ptr->encoding = source.encoding;
00201 
00202         if (getHalconEncoding(ptr->encoding) == INVALID) {
00203             throw Exception("Encoding " + ptr->encoding + " not supported");
00204         }
00205 
00206         long* pixeldata = (long*)const_cast<unsigned char*>(&source.data[0]);
00207         HalconCpp::HImage *img = new HalconCpp::HImage();
00208         if ((std::string)getHalconEncoding(source.encoding) == "mono") {
00209              img->GenImage1(getHalconChannelLength(source.encoding), source.width, source.height, pixeldata);
00210         } else {
00211             img->GenImageInterleaved(pixeldata, getHalconEncoding(source.encoding), source.width, source.height, 0,
00212                                  getHalconChannelLength(source.encoding), source.width, source.height, 0, 0, -1, 0);
00213         }
00214         ptr->image = img;
00215 
00216         return ptr;
00217     }
00218 
00219 }
00220 
00221