error_depth_publisher.cc
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Roboception GmbH
3  * All rights reserved
4  *
5  * Author: Heiko Hirschmueller
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright notice,
11  * this list of conditions and the following disclaimer.
12  *
13  * 2. Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * 3. Neither the name of the copyright holder nor the names of its contributors
18  * may be used to endorse or promote products derived from this software without
19  * specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #include "error_depth_publisher.h"
35 
37 
39 
40 namespace rc
41 {
42 ErrorDepthPublisher::ErrorDepthPublisher(ros::NodeHandle& nh, const std::string& frame_id_prefix, double _f, double _t,
43  double _scale)
44  : GenICam2RosPublisher(frame_id_prefix)
45 {
46  f = _f;
47  t = _t;
48  scale = _scale;
49 
50  pub = nh.advertise<sensor_msgs::Image>("error_depth", 1);
51 }
52 
54 {
55  return pub.getNumSubscribers() > 0;
56 }
57 
58 void ErrorDepthPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
59 {
60  if (pub.getNumSubscribers() > 0)
61  {
62  // buffer disparity and error images
63 
64  if (pixelformat == Coord3D_C16)
65  {
66  disp_list.add(buffer, part);
67  }
68  else if (pixelformat == Error8)
69  {
70  err_list.add(buffer, part);
71  }
72 
73  // get disparity and error image pair with current time stamp
74 
75  uint64_t timestamp = buffer->getTimestampNS();
76 
77  std::shared_ptr<const rcg::Image> disp = disp_list.find(timestamp);
78  std::shared_ptr<const rcg::Image> err = err_list.find(timestamp);
79 
80  if (disp && err)
81  {
82  if (disp->getWidth() == err->getWidth() && disp->getHeight() == err->getHeight())
83  {
84  // create image and initialize header
85 
86  sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
87 
88  const uint64_t freq = 1000000000ul;
89 
90  im->header.seq = seq++;
91  im->header.stamp.sec = timestamp / freq;
92  im->header.stamp.nsec = timestamp - freq * im->header.stamp.sec;
93  im->header.frame_id = frame_id;
94 
95  // set image size
96 
97  im->width = static_cast<uint32_t>(disp->getWidth());
98  im->height = static_cast<uint32_t>(disp->getHeight());
99 
100  // get pointer to image data in buffer
101 
102  size_t dpx = disp->getXPadding();
103  const uint8_t* dps = disp->getPixels();
104 
105  size_t epx = err->getXPadding();
106  const uint8_t* eps = err->getPixels();
107 
108  // convert image data
109 
111  im->is_bigendian = rcg::isHostBigEndian();
112  im->step = im->width * sizeof(float);
113 
114  im->data.resize(im->step * im->height);
115  float* pt = reinterpret_cast<float*>(&im->data[0]);
116 
117  float s = scale * f * im->width * t;
118 
119  bool bigendian = disp->isBigEndian();
120 
121  for (uint32_t k = 0; k < im->height; k++)
122  {
123  for (uint32_t i = 0; i < im->width; i++)
124  {
125  float d;
126 
127  if (bigendian)
128  {
129  d = scale * ((dps[0] << 8) | dps[1]);
130  }
131  else
132  {
133  d = scale * ((dps[1] << 8) | dps[0]);
134  }
135 
136  dps += 2;
137 
138  if (d > 0)
139  {
140  *pt++ = *eps * s / (d * d);
141  }
142  else
143  {
144  *pt++ = std::numeric_limits<float>::infinity();
145  }
146 
147  eps++;
148  }
149 
150  dps += dpx;
151  eps += epx;
152  }
153 
154  // publish message
155 
156  pub.publish(im);
157  }
158  else
159  {
160  ROS_ERROR_STREAM("Size of disparity and error images differ: " << disp->getWidth() << "x" << disp->getHeight()
161  << " != " << err->getWidth() << "x"
162  << err->getHeight());
163  }
164 
165  // remove all old images, including the current ones
166 
167  disp_list.removeOld(timestamp);
168  err_list.removeOld(timestamp);
169  }
170  }
171 }
172 }
Interface for all publishers relating to images, point clouds or other stereo-camera data...
d
void publish(const boost::shared_ptr< M > &message) const
std::shared_ptr< const Image > find(uint64_t timestamp) const
XmlRpcServer s
Coord3D_C16
bool used() override
Returns true if there are subscribers to the topic.
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
void removeOld(uint64_t timestamp)
#define Error8
const std::string TYPE_32FC1
void add(const std::shared_ptr< const Image > &image)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint64_t getTimestampNS() const
uint32_t getNumSubscribers() const
bool isHostBigEndian()
#define ROS_ERROR_STREAM(args)
ErrorDepthPublisher(ros::NodeHandle &nh, const std::string &frame_id_prefix, double f, double t, double scale)
Initialization of publisher for depth errors.


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Sat Feb 13 2021 03:42:55