depth_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 "depth_publisher.h"
35 
37 
39 
40 namespace rc
41 {
42 DepthPublisher::DepthPublisher(ros::NodeHandle& nh, const std::string& frame_id_prefix, double f, double t,
43  double _scale)
44  : GenICam2RosPublisher(frame_id_prefix)
45 {
46  scale = f * t / _scale;
47 
48  pub = nh.advertise<sensor_msgs::Image>("depth", 1);
49 }
50 
52 {
53  return pub.getNumSubscribers() > 0;
54 }
55 
56 void DepthPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
57 {
58  if (pub.getNumSubscribers() > 0 && pixelformat == Coord3D_C16)
59  {
60  // create image and initialize header
61 
62  sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
63 
64  const uint64_t freq = 1000000000ul;
65  uint64_t time = buffer->getTimestampNS();
66 
67  im->header.seq = seq++;
68  im->header.stamp.sec = time / freq;
69  im->header.stamp.nsec = time - freq * im->header.stamp.sec;
70  im->header.frame_id = frame_id;
71 
72  // set image size
73 
74  im->width = static_cast<uint32_t>(buffer->getWidth(part));
75  im->height = static_cast<uint32_t>(buffer->getHeight(part));
76 
77  // get pointer to image data in buffer
78 
79  size_t px = buffer->getXPadding(part);
80  const uint8_t* ps = static_cast<const uint8_t*>(buffer->getBase(part));
81 
82  // convert image data
83 
85  im->is_bigendian = rcg::isHostBigEndian();
86  im->step = im->width * sizeof(float);
87 
88  im->data.resize(im->step * im->height);
89  float* pt = reinterpret_cast<float*>(&im->data[0]);
90 
91  bool bigendian = buffer->isBigEndian();
92 
93  float s = scale * im->width;
94 
95  for (uint32_t k = 0; k < im->height; k++)
96  {
97  for (uint32_t i = 0; i < im->width; i++)
98  {
99  uint16_t d;
100 
101  if (bigendian)
102  {
103  d = (ps[0] << 8) | ps[1];
104  }
105  else
106  {
107  d = (ps[1] << 8) | ps[0];
108  }
109 
110  ps += 2;
111 
112  if (d != 0)
113  {
114  *pt++ = s / d;
115  }
116  else
117  {
118  *pt++ = std::numeric_limits<float>::quiet_NaN();
119  }
120  }
121 
122  ps += px;
123  }
124 
125  // publish message
126 
127  pub.publish(im);
128  }
129 }
130 }
Interface for all publishers relating to images, point clouds or other stereo-camera data...
d
void publish(const boost::shared_ptr< M > &message) const
XmlRpcServer s
Coord3D_C16
size_t getXPadding(std::uint32_t part) const
size_t getWidth(std::uint32_t part) const
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)
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.
DepthPublisher(ros::NodeHandle &nh, const std::string &frame_id_prefix, double f, double t, double scale)
Initialization of publisher.
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