points2_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 "points2_publisher.h"
00035 
00036 #include <rc_genicam_api/pixel_formats.h>
00037 
00038 #include <sensor_msgs/PointCloud2.h>
00039 
00040 namespace rc
00041 {
00042 
00043 Points2Publisher::Points2Publisher(ros::NodeHandle &nh, std::string frame_id_prefix,
00044                                    double _f, double _t, double _scale)
00045         : GenICam2RosPublisher(frame_id_prefix), left_list(50)
00046 {
00047   f=_f;
00048   t=_t;
00049   scale=_scale;
00050 
00051   pub=nh.advertise<sensor_msgs::PointCloud2>("points2", 1);
00052 }
00053 
00054 bool Points2Publisher::used()
00055 {
00056   return pub.getNumSubscribers() > 0;
00057 }
00058 
00059 void Points2Publisher::publish(const rcg::Buffer *buffer, uint64_t pixelformat)
00060 {
00061   if (pub.getNumSubscribers() > 0)
00062   {
00063     // buffer left and disparity images
00064 
00065     if (pixelformat == Mono8 || pixelformat == YCbCr411_8)
00066     {
00067       left_list.add(buffer);
00068     }
00069     else if (pixelformat == Coord3D_C16)
00070     {
00071       disp_list.add(buffer);
00072     }
00073 
00074     // get corresponding left and disparity image
00075 
00076     uint64_t timestamp=buffer->getTimestampNS();
00077 
00078     std::shared_ptr<const rcg::Image> left=left_list.find(timestamp);
00079     std::shared_ptr<const rcg::Image> disp=disp_list.find(timestamp);
00080 
00081     if (left && disp)
00082     {
00083       // determine integer factor between size of left and disparity image
00084 
00085       uint32_t lw=left->getWidth();
00086       uint32_t lh=left->getHeight();
00087 
00088       if (lh > lw) // there may be a stacked right image
00089       {
00090         lh>>=1;
00091       }
00092 
00093       int ds=(lw+disp->getWidth()-1)/disp->getWidth();
00094 
00095       if ((lw+ds-1)/ds == disp->getWidth() && (lh+ds-1)/ds == disp->getHeight())
00096       {
00097         // allocate new image message and set meta information
00098 
00099         sensor_msgs::PointCloud2Ptr p=boost::make_shared<sensor_msgs::PointCloud2>();
00100 
00101         const uint64_t freq=1000000000ul;
00102 
00103         p->header.seq=seq++;
00104         p->header.stamp.sec=timestamp/freq;
00105         p->header.stamp.nsec=timestamp-freq*p->header.stamp.sec;
00106         p->header.frame_id=frame_id;
00107 
00108         // set meta data of point cloud
00109 
00110         p->width=lw/ds; // consider only full pixels if downscaled
00111         p->height=lh/ds; // consider only full pixels if downscaled
00112 
00113         p->is_bigendian=rcg::isHostBigEndian();
00114         p->is_dense=false;
00115 
00116         p->fields.resize(4);
00117         p->fields[0].name="x";
00118         p->fields[0].offset=0;
00119         p->fields[0].count=1;
00120         p->fields[0].datatype=sensor_msgs::PointField::FLOAT32;
00121         p->fields[1].name="y";
00122         p->fields[1].offset=4;
00123         p->fields[1].count=1;
00124         p->fields[1].datatype=sensor_msgs::PointField::FLOAT32;
00125         p->fields[2].name="z";
00126         p->fields[2].offset=8;
00127         p->fields[2].count=1;
00128         p->fields[2].datatype=sensor_msgs::PointField::FLOAT32;
00129         p->fields[3].name="rgb";
00130         p->fields[3].offset=12;
00131         p->fields[3].count=1;
00132         p->fields[3].datatype=sensor_msgs::PointField::FLOAT32;
00133 
00134         p->point_step=16;
00135         p->row_step=p->point_step*p->width;
00136 
00137         // allocate memory
00138 
00139         p->data.resize(p->row_step*p->height);
00140         float *pd=reinterpret_cast<float *>(&p->data[0]);
00141 
00142         // pointer to disparity data
00143 
00144         const uint8_t *dps=disp->getPixels();
00145         size_t dstep=disp->getWidth()*sizeof(uint16_t)+disp->getXPadding();
00146 
00147         // convert disparity to point cloud using left image for texture
00148 
00149         float ff=f*disp->getWidth();
00150 
00151         bool bigendian=disp->isBigEndian();
00152 
00153         for (uint32_t k=0; k<p->height; k++)
00154         {
00155           for (uint32_t i=0; i<p->width; i++)
00156           {
00157             // get disparity
00158 
00159             uint32_t j=i<<1;
00160 
00161             float d;
00162 
00163             if (bigendian)
00164             {
00165               d=scale*((dps[j]<<8)|dps[j+1]);
00166             }
00167             else
00168             {
00169               d=scale*((dps[j+1]<<8)|dps[j]);
00170             }
00171 
00172             // if disparity is valid and color can be obtained
00173 
00174             if (d > 0)
00175             {
00176               // reconstruct 3D point
00177 
00178               pd[0]=(i+0.5-disp->getWidth()/2.0)*t/d;
00179               pd[1]=(k+0.5-disp->getHeight()/2.0)*t/d;
00180               pd[2]=ff*t/d;
00181 
00182               // store color of point
00183 
00184               uint8_t rgb[3];
00185               rcg::getColor(rgb, left, ds, i, k);
00186 
00187               uint8_t *bgra=reinterpret_cast<uint8_t *>(pd+3);
00188 
00189               bgra[0]=rgb[2];
00190               bgra[1]=rgb[1];
00191               bgra[2]=rgb[0];
00192               bgra[3]=0;
00193             }
00194             else
00195             {
00196               for (int i=0; i<4; i++)
00197               {
00198                 pd[i]=std::numeric_limits<float>::quiet_NaN();
00199               }
00200             }
00201 
00202             pd+=4;
00203           }
00204 
00205           dps+=dstep;
00206         }
00207 
00208         // publish message
00209 
00210         pub.publish(p);
00211       }
00212       else
00213       {
00214         ROS_ERROR_STREAM("Size of left and disparity image must differ only by an integer factor: " <<
00215                          left->getWidth() << "x" << left->getHeight() << " != " <<
00216                          disp->getWidth() << "x" << disp->getHeight());
00217       }
00218 
00219       // remove all old images, including the current ones
00220 
00221       left_list.removeOld(timestamp);
00222       disp_list.removeOld(timestamp);
00223     }
00224   }
00225 }
00226 
00227 }


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