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 #include "error_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 ErrorDepthPublisher::ErrorDepthPublisher(ros::NodeHandle &nh, std::string frame_id_prefix, double _f, double _t,
00044 double _scale)
00045 : GenICam2RosPublisher(frame_id_prefix)
00046 {
00047 f=_f;
00048 t=_t;
00049 scale=_scale;
00050
00051 pub=nh.advertise<sensor_msgs::Image>("error_depth", 1);
00052 }
00053
00054 bool ErrorDepthPublisher::used()
00055 {
00056 return pub.getNumSubscribers() > 0;
00057 }
00058
00059 void ErrorDepthPublisher::publish(const rcg::Buffer *buffer, uint64_t pixelformat)
00060 {
00061 if (pub.getNumSubscribers() > 0)
00062 {
00063
00064
00065 if (pixelformat == Coord3D_C16)
00066 {
00067 disp_list.add(buffer);
00068 }
00069 else if (pixelformat == Error8)
00070 {
00071 err_list.add(buffer);
00072 }
00073
00074
00075
00076 uint64_t timestamp=buffer->getTimestampNS();
00077
00078 std::shared_ptr<const rcg::Image> disp=disp_list.find(timestamp);
00079 std::shared_ptr<const rcg::Image> err=err_list.find(timestamp);
00080
00081 if (disp && err)
00082 {
00083 if (disp->getWidth() == err->getWidth() && disp->getHeight() == err->getHeight())
00084 {
00085
00086
00087 sensor_msgs::ImagePtr im=boost::make_shared<sensor_msgs::Image>();
00088
00089 const uint64_t freq=1000000000ul;
00090
00091 im->header.seq=seq++;
00092 im->header.stamp.sec=timestamp/freq;
00093 im->header.stamp.nsec=timestamp-freq*im->header.stamp.sec;
00094 im->header.frame_id=frame_id;
00095
00096
00097
00098 im->width=static_cast<uint32_t>(disp->getWidth());
00099 im->height=static_cast<uint32_t>(disp->getHeight());
00100
00101
00102
00103 size_t dpx=disp->getXPadding();
00104 const uint8_t *dps=disp->getPixels();
00105
00106 size_t epx=err->getXPadding();
00107 const uint8_t *eps=err->getPixels();
00108
00109
00110
00111 im->encoding=sensor_msgs::image_encodings::TYPE_32FC1;
00112 im->is_bigendian=rcg::isHostBigEndian();
00113 im->step=im->width*sizeof(float);
00114
00115 im->data.resize(im->step*im->height);
00116 float *pt=reinterpret_cast<float *>(&im->data[0]);
00117
00118 float s=scale*f*im->width*t;
00119
00120 bool bigendian=disp->isBigEndian();
00121
00122 for (uint32_t k=0; k<im->height; k++)
00123 {
00124 for (uint32_t i=0; i<im->width; i++)
00125 {
00126 float d;
00127
00128 if (bigendian)
00129 {
00130 d=scale*((dps[0]<<8)|dps[1]);
00131 }
00132 else
00133 {
00134 d=scale*((dps[1]<<8)|dps[0]);
00135 }
00136
00137 dps+=2;
00138
00139 if (d > 0)
00140 {
00141 *pt++=*eps*s/(d*d);
00142 }
00143 else
00144 {
00145 *pt++=std::numeric_limits<float>::infinity();
00146 }
00147
00148 eps++;
00149 }
00150
00151 dps+=dpx;
00152 eps+=epx;
00153 }
00154
00155
00156
00157 pub.publish(im);
00158 }
00159 else
00160 {
00161 ROS_ERROR_STREAM("Size of disparity and error images differ: " <<
00162 disp->getWidth() << "x" << disp->getHeight() << " != " <<
00163 err->getWidth() << "x" << err->getHeight());
00164 }
00165
00166
00167
00168 disp_list.removeOld(timestamp);
00169 err_list.removeOld(timestamp);
00170 }
00171 }
00172 }
00173
00174 }