disparity_color_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 
35 
37 
39 
40 namespace rc
41 {
43  const std::string& frame_id_prefix, double _scale)
44  : GenICam2RosPublisher(frame_id_prefix)
45 {
46  scale = _scale;
47  disprange = 0;
48 
49  pub = it.advertise("disparity_color", 1);
50 }
51 
53 {
54  disprange = _disprange;
55 }
56 
58 {
59  return pub.getNumSubscribers() > 0;
60 }
61 
62 void DisparityColorPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
63 {
64  if (pub.getNumSubscribers() > 0 && pixelformat == Coord3D_C16)
65  {
66  // create image and initialize header
67 
68  sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
69 
70  const uint64_t freq = 1000000000ul;
71  uint64_t time = buffer->getTimestampNS();
72 
73  im->header.seq = seq++;
74  im->header.stamp.sec = time / freq;
75  im->header.stamp.nsec = time - freq * im->header.stamp.sec;
76  im->header.frame_id = frame_id;
77 
78  // set image size
79 
80  im->width = static_cast<uint32_t>(buffer->getWidth(part));
81  im->height = static_cast<uint32_t>(buffer->getHeight(part));
82  im->is_bigendian = rcg::isHostBigEndian();
83 
84  // get pointer to image data in buffer
85 
86  size_t px = buffer->getXPadding(part);
87  const uint8_t* ps = static_cast<const uint8_t*>(buffer->getBase(part));
88 
89  // ensure that current disprange setting is sufficient
90 
91  bool bigendian = buffer->isBigEndian();
92 
93  int drange = disprange;
94 
95  {
96  int dmax = 0;
97  const uint8_t* p = ps;
98 
99  if (bigendian)
100  {
101  for (uint32_t k = 0; k < im->height; k++)
102  {
103  for (uint32_t i = 0; i < im->width; i++)
104  {
105  dmax = std::max(dmax, (static_cast<int>(p[0]) << 8) | p[1]);
106  p+=2;
107  }
108  }
109  }
110  else
111  {
112  for (uint32_t k = 0; k < im->height; k++)
113  {
114  for (uint32_t i = 0; i < im->width; i++)
115  {
116  dmax = std::max(dmax, (static_cast<int>(p[1]) << 8) | p[0]);
117  p+=2;
118  }
119  }
120  }
121 
122  drange = std::max(disprange, static_cast<int>(std::ceil(dmax * scale)));
123  }
124 
125  // convert image data
126 
127  im->encoding = sensor_msgs::image_encodings::RGB8;
128  im->step = 3 * im->width * sizeof(uint8_t);
129 
130  im->data.resize(im->step * im->height);
131  uint8_t* pt = reinterpret_cast<uint8_t*>(&im->data[0]);
132 
133  for (uint32_t k = 0; k < im->height; k++)
134  {
135  for (uint32_t i = 0; i < im->width; i++)
136  {
137  uint16_t d;
138 
139  if (bigendian)
140  {
141  d = (ps[0] << 8) | ps[1];
142  }
143  else
144  {
145  d = (ps[1] << 8) | ps[0];
146  }
147 
148  ps += 2;
149 
150  if (d != 0)
151  {
152  double v = scale * d / drange;
153  v = v / 1.15 + 0.1;
154 
155  double r = std::max(0.0, std::min(1.0, (1.5 - 4 * fabs(v - 0.75))));
156  double g = std::max(0.0, std::min(1.0, (1.5 - 4 * fabs(v - 0.5))));
157  double b = std::max(0.0, std::min(1.0, (1.5 - 4 * fabs(v - 0.25))));
158 
159  *pt++ = 255 * r + 0.5;
160  *pt++ = 255 * g + 0.5;
161  *pt++ = 255 * b + 0.5;
162  }
163  else
164  {
165  *pt++ = 0;
166  *pt++ = 0;
167  *pt++ = 0;
168  }
169  }
170 
171  ps += px;
172  }
173 
174  // publish message
175 
176  pub.publish(im);
177  }
178 }
179 }
Interface for all publishers relating to images, point clouds or other stereo-camera data...
d
bool used() override
Returns true if there are subscribers to the topic.
Coord3D_C16
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
size_t getXPadding(std::uint32_t part) const
DisparityColorPublisher(image_transport::ImageTransport &it, const std::string &frame_id_prefix, double scale)
Initialization of publisher.
uint32_t getNumSubscribers() const
size_t getWidth(std::uint32_t part) const
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
image_transport::Publisher pub
void * getBase(std::uint32_t part) const
void publish(const sensor_msgs::Image &message) const
uint64_t getTimestampNS() const
bool isBigEndian() const
bool isHostBigEndian()
size_t getHeight(std::uint32_t part) const
void setDisprange(int disprange)
Set the disparity range for scaling of images.


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Wed Mar 20 2019 07:55:49