image_publisher.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2017 Roboception GmbH
00003  * All rights reserved
00004  *
00005  * Author: Heiko Hirschmueller
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  * 1. Redistributions of source code must retain the above copyright notice,
00011  * this list of conditions and the following disclaimer.
00012  *
00013  * 2. Redistributions in binary form must reproduce the above copyright notice,
00014  * this list of conditions and the following disclaimer in the documentation
00015  * and/or other materials provided with the distribution.
00016  *
00017  * 3. Neither the name of the copyright holder nor the names of its contributors
00018  * may be used to endorse or promote products derived from this software without
00019  * specific prior written permission.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00022  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00023  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00024  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
00025  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00026  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00027  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00028  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00029  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00030  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  * POSSIBILITY OF SUCH DAMAGE.
00032  */
00033 
00034 #include "image_publisher.h"
00035 
00036 #include <rc_genicam_api/image.h>
00037 #include <rc_genicam_api/pixel_formats.h>
00038 
00039 #include <sensor_msgs/image_encodings.h>
00040 
00041 namespace rc
00042 {
00043 
00044 ImagePublisher::ImagePublisher(image_transport::ImageTransport &it, std::string frame_id_prefix,
00045                                bool _left, bool _color)
00046         : GenICam2RosPublisher(frame_id_prefix)
00047 {
00048   left=_left;
00049   color=_color;
00050   seq=0;
00051 
00052   if (left)
00053   {
00054     if (color)
00055     {
00056       pub=it.advertise("left/image_rect_color", 1);
00057     }
00058     else
00059     {
00060       pub=it.advertise("left/image_rect", 1);
00061     }
00062   }
00063   else
00064   {
00065     if (color)
00066     {
00067       pub=it.advertise("right/image_rect_color", 1);
00068     }
00069     else
00070     {
00071       pub=it.advertise("right/image_rect", 1);
00072     }
00073   }
00074 }
00075 
00076 bool ImagePublisher::used()
00077 {
00078   return pub.getNumSubscribers() > 0;
00079 }
00080 
00081 namespace
00082 {
00083 
00088 uint8_t clamp8(int v)
00089 {
00090   if (v < 0) { v=0; }
00091 
00092   if (v > 255) { v=255; }
00093 
00094   return static_cast<uint8_t>(v);
00095 }
00096 
00097 }
00098 
00099 void ImagePublisher::publish(const rcg::Buffer *buffer, uint64_t pixelformat)
00100 {
00101   if (pub.getNumSubscribers() > 0 && (pixelformat == Mono8 || pixelformat == YCbCr411_8))
00102   {
00103     // create image and initialize header
00104 
00105     sensor_msgs::ImagePtr im=boost::make_shared<sensor_msgs::Image>();
00106 
00107     const uint64_t freq=1000000000ul;
00108     uint64_t time=buffer->getTimestampNS();
00109 
00110     im->header.seq=seq++;
00111     im->header.stamp.sec=time/freq;
00112     im->header.stamp.nsec=time-freq*im->header.stamp.sec;
00113     im->header.frame_id=frame_id;
00114 
00115     // set image size
00116 
00117     im->width=static_cast<uint32_t>(buffer->getWidth());
00118     im->height=static_cast<uint32_t>(buffer->getHeight());
00119     im->is_bigendian=false;
00120 
00121     bool stacked=false;
00122 
00123     if (im->height > im->width)
00124     {
00125       stacked=true;
00126       im->height>>=1;
00127     }
00128 
00129     // get pointer to image data in buffer
00130 
00131     const uint8_t *ps=static_cast<const uint8_t *>(buffer->getBase())+buffer->getImageOffset();
00132     size_t pstep=im->width+buffer->getXPadding();
00133 
00134     if (pixelformat == YCbCr411_8)
00135     {
00136       pstep=(im->width>>2)*6+buffer->getXPadding();
00137     }
00138 
00139     if (!left)
00140     {
00141       if (stacked)
00142       {
00143         ps+=pstep*im->height;
00144       }
00145       else
00146       {
00147         return; // buffer does not contain a right image
00148       }
00149     }
00150 
00151     // convert image data
00152 
00153     if (color) // convert to color
00154     {
00155       im->encoding=sensor_msgs::image_encodings::RGB8;
00156       im->step=3*im->width*sizeof(uint8_t);
00157 
00158       im->data.resize(im->step*im->height);
00159       uint8_t *pt=reinterpret_cast<uint8_t *>(&im->data[0]);
00160 
00161       if (pixelformat == Mono8) // convert from monochrome
00162       {
00163         return; // do not convert from monochrome, skip instead
00164       }
00165       else if (pixelformat == YCbCr411_8) // convert from YUV 411
00166       {
00167         for (uint32_t k=0; k<im->height; k++)
00168         {
00169           for (uint32_t i=0; i<im->width; i+=4)
00170           {
00171             rcg::convYCbCr411toQuadRGB(pt, ps, i);
00172             pt+=12;
00173           }
00174 
00175           ps+=pstep;
00176         }
00177       }
00178     }
00179     else // convert to monochrome
00180     {
00181       im->encoding=sensor_msgs::image_encodings::MONO8;
00182       im->step=im->width*sizeof(uint8_t);
00183 
00184       im->data.resize(im->step*im->height);
00185       uint8_t *pt=reinterpret_cast<uint8_t *>(&im->data[0]);
00186 
00187       if (pixelformat == Mono8) // copy monochrome image
00188       {
00189         for (uint32_t k=0; k<im->height; k++)
00190         {
00191           for (uint32_t i=0; i<im->width; i++)
00192           {
00193             *pt++=ps[i];
00194           }
00195 
00196           ps+=pstep;
00197         }
00198       }
00199       else if (pixelformat == YCbCr411_8) // copy monochrome part of YUV 411 image
00200       {
00201         for (uint32_t k=0; k<im->height; k++)
00202         {
00203           int j=0;
00204 
00205           for (uint32_t i=0; i<im->width; i+=4)
00206           {
00207             *pt++=ps[j];
00208             *pt++=ps[j+1];
00209             *pt++=ps[j+3];
00210             *pt++=ps[j+4];
00211             j+=6;
00212           }
00213 
00214           ps+=pstep;
00215         }
00216       }
00217     }
00218 
00219     // publish message
00220 
00221     pub.publish(im);
00222   }
00223 }
00224 
00225 }


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Thu Jun 6 2019 20:43:05