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 _f, double _t, double _scale)
44  : GenICam2RosPublisher(frame_id_prefix)
45 {
46  seq = 0;
47  f = _f;
48  t = _t;
49  scale = _scale;
50  mindepth = 2.5*t;
51  maxdepth = 100;
52 
53  pub = it.advertise("disparity_color", 1);
54 }
55 
56 void DisparityColorPublisher::setDepthRange(double _mindepth, double _maxdepth)
57 {
58  mindepth = std::max(2.5*t, _mindepth);
59  maxdepth = std::max(mindepth, _maxdepth);
60 }
61 
63 {
64  return pub.getNumSubscribers() > 0;
65 }
66 
67 void DisparityColorPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
68 {
69  if (pub.getNumSubscribers() > 0 && pixelformat == Coord3D_C16)
70  {
71  // compute minimum and maximum disparity
72 
73  int dmin=static_cast<int>(std::floor(f*buffer->getWidth(part)*t/maxdepth));
74  int dmax=static_cast<int>(std::ceil(f*buffer->getWidth(part)*t/mindepth));
75  int drange=dmax-dmin+1;
76 
77  // create image and initialize header
78 
79  sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
80 
81  const uint64_t freq = 1000000000ul;
82  uint64_t time = buffer->getTimestampNS();
83 
84  im->header.seq = seq++;
85  im->header.stamp.sec = time / freq;
86  im->header.stamp.nsec = time - freq * im->header.stamp.sec;
87  im->header.frame_id = frame_id;
88 
89  // set image size
90 
91  im->width = static_cast<uint32_t>(buffer->getWidth(part));
92  im->height = static_cast<uint32_t>(buffer->getHeight(part));
93  im->is_bigendian = rcg::isHostBigEndian();
94 
95  // get pointer to image data in buffer
96 
97  size_t px = buffer->getXPadding(part);
98  const uint8_t* ps = static_cast<const uint8_t*>(buffer->getBase(part));
99 
100  // convert image data
101 
102  bool bigendian = buffer->isBigEndian();
103 
104  im->encoding = sensor_msgs::image_encodings::RGB8;
105  im->step = 3 * im->width * sizeof(uint8_t);
106 
107  im->data.resize(im->step * im->height);
108  uint8_t* pt = reinterpret_cast<uint8_t*>(&im->data[0]);
109 
110  for (uint32_t k = 0; k < im->height; k++)
111  {
112  for (uint32_t i = 0; i < im->width; i++)
113  {
114  uint16_t d;
115 
116  if (bigendian)
117  {
118  d = (ps[0] << 8) | ps[1];
119  }
120  else
121  {
122  d = (ps[1] << 8) | ps[0];
123  }
124 
125  ps += 2;
126 
127  if (d != 0)
128  {
129  double v = (scale * d - dmin) / drange;
130  v = v / 1.15 + 0.1;
131 
132  double r = std::max(0.0, std::min(1.0, (1.5 - 4 * fabs(v - 0.75))));
133  double g = std::max(0.0, std::min(1.0, (1.5 - 4 * fabs(v - 0.5))));
134  double b = std::max(0.0, std::min(1.0, (1.5 - 4 * fabs(v - 0.25))));
135 
136  *pt++ = 255 * r + 0.5;
137  *pt++ = 255 * g + 0.5;
138  *pt++ = 255 * b + 0.5;
139  }
140  else
141  {
142  *pt++ = 0;
143  *pt++ = 0;
144  *pt++ = 0;
145  }
146  }
147 
148  ps += px;
149  }
150 
151  // publish message
152 
153  pub.publish(im);
154  }
155 }
156 }
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
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()
DisparityColorPublisher(image_transport::ImageTransport &it, const std::string &frame_id_prefix, double f, double t, double scale)
Initialization of publisher.
size_t getHeight(std::uint32_t part) const
void setDepthRange(double _mindepth, double _maxdepth)
Set the depth range of the disparity images.


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