disparity_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 "disparity_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  sub_callback = sub_changed;
48  pub = nh.advertise<stereo_msgs::DisparityImage>("disparity", 1,
49  boost::bind(&GenICam2RosPublisher::subChanged, this, _1),
50  boost::bind(&GenICam2RosPublisher::subChanged, this, _1));
51 }
52 
54 {
55  return pub.getNumSubscribers() > 0;
56 }
57 
58 void DisparityPublisher::requiresComponents(int& components, bool& color)
59 {
60  if (pub.getNumSubscribers() > 0)
61  {
62  components |= ComponentDisparity;
63  }
64 }
65 
66 void DisparityPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
67 {
68  if (nodemap && pub.getNumSubscribers() > 0 && pixelformat == Coord3D_C16)
69  {
70  // allocate new image message and set meta information
71 
72  stereo_msgs::DisparityImagePtr p = boost::make_shared<stereo_msgs::DisparityImage>();
73 
74  uint64_t time = buffer->getTimestampNS();
75 
76  p->header.seq = 0;
77  p->header.stamp.sec = time / 1000000000ul;
78  p->header.stamp.nsec = time % 1000000000ul;
79  p->header.frame_id = frame_id;
80 
81  // get some information from the buffer
82 
83  rcg::setEnum(nodemap, "ChunkComponentSelector", "Disparity", true);
84  double f = rcg::getFloat(nodemap, "ChunkScan3dFocalLength", 0, 0, true);
85  double t = rcg::getFloat(nodemap, "ChunkScan3dBaseline", 0, 0, true);
86  float scale = rcg::getFloat(nodemap, "ChunkScan3dCoordinateScale", 0, 0, true);
87 
88  double mindepth = rcg::getFloat(nodemap, "DepthMinDepth", 0, 0, true);
89  mindepth = std::max(mindepth, 2.5*t);
90  int disprange = static_cast<int>(std::ceil(f*t/mindepth));
91 
92  // prepare size and format of outgoing image
93 
94  p->image.header = p->header;
95  p->image.width = static_cast<uint32_t>(buffer->getWidth(part));
96  p->image.height = static_cast<uint32_t>(buffer->getHeight(part));
97  p->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
98  p->image.is_bigendian = rcg::isHostBigEndian();
99  p->image.step = p->image.width * sizeof(float);
100 
101  size_t px = buffer->getXPadding(part);
102  const uint8_t* ps = static_cast<const uint8_t*>(buffer->getBase(part));
103 
104  // convert image information
105 
106  p->image.data.resize(p->image.step * p->image.height);
107 
108  float* pt = reinterpret_cast<float*>(&p->image.data[0]);
109  float dmax = 0;
110 
111  bool bigendian = buffer->isBigEndian();
112 
113  for (uint32_t k = 0; k < p->image.height; k++)
114  {
115  if (bigendian)
116  {
117  for (uint32_t i = 0; i < p->image.width; i++)
118  {
119  uint16_t d = (ps[0] << 8) | ps[1];
120 
121  *pt = -1.0f;
122 
123  if (d != 0)
124  {
125  *pt = scale * d;
126  dmax = std::max(dmax, *pt);
127  }
128 
129  ps += 2;
130  pt++;
131  }
132  }
133  else
134  {
135  for (uint32_t i = 0; i < p->image.width; i++)
136  {
137  uint16_t d = (ps[1] << 8) | ps[0];
138 
139  *pt = -1.0f;
140 
141  if (d != 0)
142  {
143  *pt = scale * d;
144  dmax = std::max(dmax, *pt);
145  }
146 
147  ps += 2;
148  pt++;
149  }
150  }
151 
152  ps += px;
153  }
154 
155  p->f = f;
156  p->T = t;
157  p->valid_window.x_offset = 0;
158  p->valid_window.y_offset = 0;
159  p->valid_window.width = p->image.width;
160  p->valid_window.height = p->image.height;
161  p->min_disparity = 0;
162  p->max_disparity = std::max(dmax, static_cast<float>(disprange));
163  p->delta_d = scale;
164 
165  // publish message
166 
167  pub.publish(p);
168  }
169 }
170 } // namespace rc
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
f
static const int ComponentDisparity
bool used() override
Returns true if there are subscribers to the topic.
std::function< void()> sub_callback
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.
Coord3D_C16
size_t getXPadding(std::uint32_t part) const
size_t getWidth(std::uint32_t part) const
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 * getBase(std::uint32_t part) const
const std::string TYPE_32FC1
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 isBigEndian() const
bool isHostBigEndian()
DisparityPublisher(ros::NodeHandle &nh, const std::string &frame_id, std::function< void()> &sub_changed)
std::shared_ptr< GenApi::CNodeMapRef > nodemap
size_t getHeight(std::uint32_t part) const


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