error_depth_publisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020 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 #include <rc_genicam_api/config.h>
38 
40 
41 namespace rc
42 {
44  std::function<void()>& sub_changed)
45  : GenICam2RosPublisher(frame_id)
46 {
47  f = 0;
48  t = 0;
49  invalid = -1;
50  scale = 1;
51 
52  sub_callback = sub_changed;
53  pub = nh.advertise<sensor_msgs::Image>("error_depth", 1, boost::bind(&GenICam2RosPublisher::subChanged, this, _1),
54  boost::bind(&GenICam2RosPublisher::subChanged, this, _1));
55 }
56 
58 {
59  return pub.getNumSubscribers() > 0;
60 }
61 
62 void ErrorDepthPublisher::requiresComponents(int& components, bool& color)
63 {
64  if (pub.getNumSubscribers() > 0)
65  {
66  components |= ComponentDisparity | ComponentError;
67  }
68 }
69 
70 void ErrorDepthPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
71 {
72  if (nodemap && pub.getNumSubscribers() > 0)
73  {
74  // buffer disparity and error images
75 
76  if (pixelformat == Coord3D_C16)
77  {
78  disp_list.add(buffer, part);
79 
80  rcg::setEnum(nodemap, "ChunkComponentSelector", "Disparity", true);
81  f = rcg::getFloat(nodemap, "ChunkScan3dFocalLength", 0, 0, true);
82  t = rcg::getFloat(nodemap, "ChunkScan3dBaseline", 0, 0, true);
83 
84  invalid = -1;
85  if (rcg::getBoolean(nodemap, "ChunkScan3dInvalidDataFlag", false))
86  {
87  invalid = rcg::getFloat(nodemap, "ChunkScan3dInvalidDataValue", 0, 0, true);
88  }
89 
90  scale = rcg::getFloat(nodemap, "ChunkScan3dCoordinateScale", 0, 0, true);
91  }
92  else if (pixelformat == Error8)
93  {
94  err_list.add(buffer, part);
95  }
96 
97  // get disparity and error image pair with current time stamp
98 
99  uint64_t timestamp = buffer->getTimestampNS();
100 
101  std::shared_ptr<const rcg::Image> disp = disp_list.find(timestamp);
102  std::shared_ptr<const rcg::Image> err = err_list.find(timestamp);
103 
104  if (disp && err)
105  {
106  if (disp->getWidth() == err->getWidth() && disp->getHeight() == err->getHeight())
107  {
108  // create image and initialize header
109 
110  sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
111 
112  im->header.seq = 0;
113  im->header.stamp.sec = timestamp / 1000000000ul;
114  im->header.stamp.nsec = timestamp % 1000000000ul;
115  im->header.frame_id = frame_id;
116 
117  // set image size
118 
119  im->width = static_cast<uint32_t>(disp->getWidth());
120  im->height = static_cast<uint32_t>(disp->getHeight());
121 
122  // get pointer to image data in buffer
123 
124  size_t dpx = disp->getXPadding();
125  const uint8_t* dps = disp->getPixels();
126 
127  size_t epx = err->getXPadding();
128  const uint8_t* eps = err->getPixels();
129 
130  // convert image data
131 
133  im->is_bigendian = rcg::isHostBigEndian();
134  im->step = im->width * sizeof(float);
135 
136  im->data.resize(im->step * im->height);
137  float* pt = reinterpret_cast<float*>(&im->data[0]);
138 
139  float s = scale * f * t;
140 
141  bool bigendian = disp->isBigEndian();
142 
143  for (uint32_t k = 0; k < im->height; k++)
144  {
145  for (uint32_t i = 0; i < im->width; i++)
146  {
147  float d;
148 
149  if (bigendian)
150  {
151  d = scale * ((dps[0] << 8) | dps[1]);
152  }
153  else
154  {
155  d = scale * ((dps[1] << 8) | dps[0]);
156  }
157 
158  dps += 2;
159 
160  if (d != 0 && d != invalid)
161  {
162  *pt++ = *eps * s / (d * d);
163  }
164  else
165  {
166  *pt++ = std::numeric_limits<float>::infinity();
167  }
168 
169  eps++;
170  }
171 
172  dps += dpx;
173  eps += epx;
174  }
175 
176  // publish message
177 
178  pub.publish(im);
179  }
180  else
181  {
182  ROS_ERROR_STREAM("Size of disparity and error images differ: " << disp->getWidth() << "x" << disp->getHeight()
183  << " != " << err->getWidth() << "x"
184  << err->getHeight());
185  }
186 
187  // remove all old images, including the current ones
188 
189  disp_list.removeOld(timestamp);
190  err_list.removeOld(timestamp);
191  }
192  }
193 }
194 } // namespace rc
Interface for all publishers relating to images, point clouds or other stereo-camera data...
d
bool getBoolean(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false, bool igncache=false)
void publish(const boost::shared_ptr< M > &message) const
std::shared_ptr< const Image > find(uint64_t timestamp) const
static const int ComponentDisparity
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.
std::function< void()> sub_callback
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.
bool setEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception=false)
void subChanged(const ros::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
void removeOld(uint64_t timestamp)
#define Error8
const std::string TYPE_32FC1
void add(const std::shared_ptr< const Image > &image)
ErrorDepthPublisher(ros::NodeHandle &nh, const std::string &frame_id, std::function< void()> &sub_changed)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double getFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double *vmin=0, double *vmax=0, bool exception=false, bool igncache=false)
uint64_t getTimestampNS() const
uint32_t getNumSubscribers() const
bool isHostBigEndian()
#define ROS_ERROR_STREAM(args)
std::shared_ptr< GenApi::CNodeMapRef > nodemap


rc_genicam_driver
Author(s): Heiko Hirschmueller , Felix Ruess
autogenerated on Sat Feb 13 2021 03:55:07