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 "depth_publisher.h"
35 
37 #include <rc_genicam_api/config.h>
38 
40 
41 namespace rc
42 {
43 DepthPublisher::DepthPublisher(ros::NodeHandle& nh, const std::string& frame_id, std::function<void()>& sub_changed)
44  : GenICam2RosPublisher(frame_id)
45 {
46  sub_callback = sub_changed;
47  pub = nh.advertise<sensor_msgs::Image>("depth", 1, boost::bind(&GenICam2RosPublisher::subChanged, this, _1),
48  boost::bind(&GenICam2RosPublisher::subChanged, this, _1));
49 }
50 
52 {
53  return pub.getNumSubscribers() > 0;
54 }
55 
56 void DepthPublisher::requiresComponents(int& components, bool& color)
57 {
58  if (pub.getNumSubscribers() > 0)
59  {
60  components |= ComponentDisparity;
61  }
62 }
63 
64 void DepthPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
65 {
66  if (nodemap && pub.getNumSubscribers() > 0 && pixelformat == Coord3D_C16)
67  {
68  // create image and initialize header
69 
70  sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
71 
72  uint64_t time = buffer->getTimestampNS();
73 
74  im->header.seq = 0;
75  im->header.stamp.sec = time / 1000000000ul;
76  im->header.stamp.nsec = time % 1000000000ul;
77  im->header.frame_id = frame_id;
78 
79  // set image size
80 
81  im->width = static_cast<uint32_t>(buffer->getWidth(part));
82  im->height = static_cast<uint32_t>(buffer->getHeight(part));
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  // convert image data
90 
92  im->is_bigendian = rcg::isHostBigEndian();
93  im->step = im->width * sizeof(float);
94 
95  im->data.resize(im->step * im->height);
96  float* pt = reinterpret_cast<float*>(&im->data[0]);
97 
98  bool bigendian = buffer->isBigEndian();
99 
100  rcg::setEnum(nodemap, "ChunkComponentSelector", "Disparity", true);
101  double f = rcg::getFloat(nodemap, "ChunkScan3dFocalLength", 0, 0, true);
102  double t = rcg::getFloat(nodemap, "ChunkScan3dBaseline", 0, 0, true);
103 
104  float invalid = -1;
105  if (rcg::getBoolean(nodemap, "ChunkScan3dInvalidDataFlag", false))
106  {
107  invalid = rcg::getFloat(nodemap, "ChunkScan3dInvalidDataValue", 0, 0, true);
108  }
109 
110  float scale = rcg::getFloat(nodemap, "ChunkScan3dCoordinateScale", 0, 0, true);
111 
112  float s = f * t / scale;
113 
114  for (uint32_t k = 0; k < im->height; k++)
115  {
116  for (uint32_t i = 0; i < im->width; i++)
117  {
118  uint16_t d;
119 
120  if (bigendian)
121  {
122  d = (ps[0] << 8) | ps[1];
123  }
124  else
125  {
126  d = (ps[1] << 8) | ps[0];
127  }
128 
129  ps += 2;
130 
131  if (d != 0 && d != invalid)
132  {
133  *pt++ = s / d;
134  }
135  else
136  {
137  *pt++ = std::numeric_limits<float>::quiet_NaN();
138  }
139  }
140 
141  ps += px;
142  }
143 
144  // publish message
145 
146  pub.publish(im);
147  }
148 }
149 
150 } // 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
f
static const int ComponentDisparity
std::function< void()> sub_callback
XmlRpcServer s
Coord3D_C16
size_t getXPadding(std::uint32_t part) const
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.
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.
bool used() override
Returns true if there are subscribers to the topic.
void * getBase(std::uint32_t part) const
const std::string TYPE_32FC1
ros::Publisher pub
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
DepthPublisher(ros::NodeHandle &nh, const std::string &frame_id, std::function< void()> &sub_changed)
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()
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
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