depth_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 "depth_publisher.h"
00035 
00036 #include <rc_genicam_api/pixel_formats.h>
00037 
00038 #include <sensor_msgs/image_encodings.h>
00039 
00040 namespace rc
00041 {
00042 
00043 DepthPublisher::DepthPublisher(ros::NodeHandle &nh, std::string frame_id_prefix,
00044                                double f, double t, double _scale)
00045         : GenICam2RosPublisher(frame_id_prefix)
00046 {
00047   scale=f*t/_scale;
00048 
00049   pub=nh.advertise<sensor_msgs::Image>("depth", 1);
00050 }
00051 
00052 bool DepthPublisher::used()
00053 {
00054   return pub.getNumSubscribers() > 0;
00055 }
00056 
00057 void DepthPublisher::publish(const rcg::Buffer *buffer, uint64_t pixelformat)
00058 {
00059   if (pub.getNumSubscribers() > 0 && pixelformat == Coord3D_C16)
00060   {
00061     // create image and initialize header
00062 
00063     sensor_msgs::ImagePtr im=boost::make_shared<sensor_msgs::Image>();
00064 
00065     const uint64_t freq=1000000000ul;
00066     uint64_t time=buffer->getTimestampNS();
00067 
00068     im->header.seq=seq++;
00069     im->header.stamp.sec=time/freq;
00070     im->header.stamp.nsec=time-freq*im->header.stamp.sec;
00071     im->header.frame_id=frame_id;
00072 
00073     // set image size
00074 
00075     im->width=static_cast<uint32_t>(buffer->getWidth());
00076     im->height=static_cast<uint32_t>(buffer->getHeight());
00077 
00078     // get pointer to image data in buffer
00079 
00080     size_t px=buffer->getXPadding();
00081     const uint8_t *ps=static_cast<const uint8_t *>(buffer->getBase())+buffer->getImageOffset();
00082 
00083     // convert image data
00084 
00085     im->encoding=sensor_msgs::image_encodings::TYPE_32FC1;
00086     im->is_bigendian=rcg::isHostBigEndian();
00087     im->step=im->width*sizeof(float);
00088 
00089     im->data.resize(im->step*im->height);
00090     float *pt=reinterpret_cast<float *>(&im->data[0]);
00091 
00092     bool bigendian=buffer->isBigEndian();
00093 
00094     float s=scale*im->width;
00095 
00096     for (uint32_t k=0; k<im->height; k++)
00097     {
00098       for (uint32_t i=0; i<im->width; i++)
00099       {
00100         uint16_t d;
00101 
00102         if (bigendian)
00103         {
00104           d=(ps[0]<<8)|ps[1];
00105         }
00106         else
00107         {
00108           d=(ps[1]<<8)|ps[0];
00109         }
00110 
00111         ps+=2;
00112 
00113         if (d != 0)
00114         {
00115           *pt++=s/d;
00116         }
00117         else
00118         {
00119           *pt++=std::numeric_limits<float>::quiet_NaN();
00120         }
00121       }
00122 
00123       ps+=px;
00124     }
00125 
00126     // publish message
00127 
00128     pub.publish(im);
00129   }
00130 }
00131 
00132 }


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