disparity_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 "disparity_publisher.h"
35 
37 
39 
40 namespace rc
41 {
42 DisparityPublisher::DisparityPublisher(ros::NodeHandle& nh, const std::string& frame_id_prefix,
43  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 = nh.advertise<stereo_msgs::DisparityImage>("disparity", 1);
54 }
55 
56 void DisparityPublisher::setDepthRange(double _mindepth, double _maxdepth)
57 {
58  mindepth = std::max(2.5*t, _mindepth);
59  maxdepth = _maxdepth;
60 }
61 
63 {
64  return pub.getNumSubscribers() > 0;
65 }
66 
67 void DisparityPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
68 {
69  if (pub.getNumSubscribers() > 0 && pixelformat == Coord3D_C16)
70  {
71  // allocate new image message and set meta information
72 
73  stereo_msgs::DisparityImagePtr p = boost::make_shared<stereo_msgs::DisparityImage>();
74 
75  const uint64_t freq = 1000000000ul;
76  uint64_t time = buffer->getTimestampNS();
77 
78  p->header.seq = seq++;
79  p->header.stamp.sec = time / freq;
80  p->header.stamp.nsec = time - freq * p->header.stamp.sec;
81  p->header.frame_id = frame_id;
82 
83  // prepare size and format of outgoing image
84 
85  p->image.header = p->header;
86  p->image.width = static_cast<uint32_t>(buffer->getWidth(part));
87  p->image.height = static_cast<uint32_t>(buffer->getHeight(part));
88  p->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
89  p->image.is_bigendian = rcg::isHostBigEndian();
90  p->image.step = p->image.width * sizeof(float);
91 
92  size_t px = buffer->getXPadding(part);
93  const uint8_t* ps = static_cast<const uint8_t*>(buffer->getBase(part));
94 
95  // convert image information
96 
97  p->image.data.resize(p->image.step * p->image.height);
98 
99  float* pt = reinterpret_cast<float*>(&p->image.data[0]);
100  float dmax = 0;
101 
102  bool bigendian = buffer->isBigEndian();
103 
104  for (uint32_t k = 0; k < p->image.height; k++)
105  {
106  if (bigendian)
107  {
108  for (uint32_t i = 0; i < p->image.width; i++)
109  {
110  uint16_t d = (ps[0] << 8) | ps[1];
111 
112  *pt = -1.0f;
113 
114  if (d != 0)
115  {
116  *pt = scale * d;
117  dmax = std::max(dmax, *pt);
118  }
119 
120  ps += 2;
121  pt++;
122  }
123  }
124  else
125  {
126  for (uint32_t i = 0; i < p->image.width; i++)
127  {
128  uint16_t d = (ps[1] << 8) | ps[0];
129 
130  *pt = -1.0f;
131 
132  if (d != 0)
133  {
134  *pt = scale * d;
135  dmax = std::max(dmax, *pt);
136  }
137 
138  ps += 2;
139  pt++;
140  }
141  }
142 
143  ps += px;
144  }
145 
146  p->f = f * p->image.width;
147  p->T = t;
148  p->valid_window.x_offset = 0;
149  p->valid_window.y_offset = 0;
150  p->valid_window.width = p->image.width;
151  p->valid_window.height = p->image.height;
152  p->min_disparity = 0;
153  p->max_disparity = std::max(dmax, static_cast<float>(std::ceil(p->f * p->T / mindepth)));
154  p->delta_d = scale;
155 
156  // publish message
157 
158  pub.publish(p);
159  }
160 }
161 }
Interface for all publishers relating to images, point clouds or other stereo-camera data...
d
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
void publish(const boost::shared_ptr< M > &message) const
bool used() override
Returns true if there are subscribers to the topic.
Coord3D_C16
size_t getXPadding(std::uint32_t part) const
size_t getWidth(std::uint32_t part) const
void * getBase(std::uint32_t part) const
const std::string TYPE_32FC1
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint64_t getTimestampNS() const
uint32_t getNumSubscribers() const
bool isBigEndian() const
bool isHostBigEndian()
DisparityPublisher(ros::NodeHandle &nh, const std::string &frame_id_prefix, double f, double t, double scale)
Initialization of publisher.
void setDepthRange(double _mindepth, double _maxdepth)
Set the depth range of the disparity images.
size_t getHeight(std::uint32_t part) const


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