image_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 "image_publisher.h"
35 
36 #include <rc_genicam_api/image.h>
38 #include <rc_genicam_api/config.h>
39 
41 
42 namespace rc
43 {
44 ImagePublisher::ImagePublisher(image_transport::ImageTransport& it, const std::string& frame_id, bool _left,
45  bool _color, bool out1_filter, std::function<void()>& sub_changed)
46  : GenICam2RosPublisher(frame_id)
47 {
48  left = _left;
49  color = _color;
50 
51  std::string name;
52 
53  if (left)
54  {
55  name = "left/image_rect";
56  }
57  else
58  {
59  name = "right/image_rect";
60  }
61 
62  if (color)
63  {
64  name = name + "_color";
65  }
66 
67  sub_callback = sub_changed;
68 
69  pub = it.advertise(name, 1, boost::bind(&GenICam2RosPublisher::subChangedIt, this, _1),
70  boost::bind(&GenICam2RosPublisher::subChangedIt, this, _1));
71 
72  if (out1_filter)
73  {
74  pub_out1_low = it.advertise(name + "_out1_low", 1, boost::bind(&GenICam2RosPublisher::subChangedIt, this, _1),
75  boost::bind(&GenICam2RosPublisher::subChangedIt, this, _1));
76 
77  pub_out1_high = it.advertise(name + "_out1_high", 1, boost::bind(&GenICam2RosPublisher::subChangedIt, this, _1),
78  boost::bind(&GenICam2RosPublisher::subChangedIt, this, _1));
79  }
80 }
81 
83 {
85 }
86 
87 void ImagePublisher::requiresComponents(int& components, bool& _color)
88 {
90  {
91  if (left)
92  {
93  components |= ComponentIntensity;
94  }
95  else
96  {
97  components |= ComponentIntensityCombined;
98  }
99 
100  if (color)
101  _color = true;
102  }
103 }
104 
105 void ImagePublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
106 {
107  if (nodemap)
108  {
109  rcg::setEnum(nodemap, "ChunkLineSelector", "Out1", true);
110  std::string out1_mode = rcg::getEnum(nodemap, "ChunkLineSource", true);
111  bool out1 = rcg::getInteger(nodemap, "ChunkLineStatusAll", 0, 0, true) & 0x1;
112 
113  bool sub = (pub.getNumSubscribers() > 0);
114 
115  if (!out1 && pub_out1_low.getNumSubscribers() > 0)
116  sub = true;
117  if (out1 && pub_out1_high.getNumSubscribers() > 0)
118  sub = true;
119 
120  if (sub && (pixelformat == Mono8 || pixelformat == YCbCr411_8))
121  {
122  // create image and initialize header
123 
124  sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
125 
126  uint64_t time = buffer->getTimestampNS();
127 
128  im->header.seq = 0;
129  im->header.stamp.sec = time / 1000000000ul;
130  im->header.stamp.nsec = time % 1000000000ul;
131  im->header.frame_id = frame_id;
132 
133  // set image size
134 
135  im->width = static_cast<uint32_t>(buffer->getWidth(part));
136  im->height = static_cast<uint32_t>(buffer->getHeight(part));
137  im->is_bigendian = false;
138 
139  bool stacked = false;
140 
141  if (im->height > im->width)
142  {
143  stacked = true;
144  im->height >>= 1;
145  }
146 
147  // get pointer to image data in buffer
148 
149  const uint8_t* ps = static_cast<const uint8_t*>(buffer->getBase(part));
150  size_t pstep = im->width + buffer->getXPadding(part);
151 
152  if (pixelformat == YCbCr411_8)
153  {
154  pstep = (im->width >> 2) * 6 + buffer->getXPadding(part);
155  }
156 
157  if (!left)
158  {
159  if (stacked)
160  {
161  ps += pstep * im->height;
162  }
163  else
164  {
165  return; // buffer does not contain a right image
166  }
167  }
168 
169  // convert image data
170 
171  if (color) // convert to color
172  {
173  im->encoding = sensor_msgs::image_encodings::RGB8;
174  im->step = 3 * im->width * sizeof(uint8_t);
175 
176  im->data.resize(im->step * im->height);
177  uint8_t* pt = reinterpret_cast<uint8_t*>(&im->data[0]);
178 
179  if (pixelformat == Mono8) // convert from monochrome
180  {
181  return; // do not convert from monochrome, skip instead
182  }
183  else if (pixelformat == YCbCr411_8) // convert from YUV 411
184  {
185  for (uint32_t k = 0; k < im->height; k++)
186  {
187  for (uint32_t i = 0; i < im->width; i += 4)
188  {
189  rcg::convYCbCr411toQuadRGB(pt, ps, i);
190  pt += 12;
191  }
192 
193  ps += pstep;
194  }
195  }
196  }
197  else // convert to monochrome
198  {
200  im->step = im->width * sizeof(uint8_t);
201 
202  im->data.resize(im->step * im->height);
203  uint8_t* pt = reinterpret_cast<uint8_t*>(&im->data[0]);
204 
205  if (pixelformat == Mono8) // copy monochrome image
206  {
207  for (uint32_t k = 0; k < im->height; k++)
208  {
209  for (uint32_t i = 0; i < im->width; i++)
210  {
211  *pt++ = ps[i];
212  }
213 
214  ps += pstep;
215  }
216  }
217  else if (pixelformat == YCbCr411_8) // copy monochrome part of YUV 411 image
218  {
219  for (uint32_t k = 0; k < im->height; k++)
220  {
221  int j = 0;
222 
223  for (uint32_t i = 0; i < im->width; i += 4)
224  {
225  *pt++ = ps[j];
226  *pt++ = ps[j + 1];
227  *pt++ = ps[j + 3];
228  *pt++ = ps[j + 4];
229  j += 6;
230  }
231 
232  ps += pstep;
233  }
234  }
235  }
236 
237  // publish message
238 
239  pub.publish(im);
240 
241  if (!out1)
242  pub_out1_low.publish(im);
243  if (out1)
245  }
246  }
247 }
248 
249 } // namespace rc
Interface for all publishers relating to images, point clouds or other stereo-camera data...
bool used() override
Returns true if there are subscribers to the topic.
Mono8
std::function< void()> sub_callback
image_transport::Publisher pub_out1_low
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
size_t getXPadding(std::uint32_t part) const
int64_t getInteger(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, int64_t *vmin=0, int64_t *vmax=0, bool exception=false, bool igncache=false)
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.
YCbCr411_8
uint32_t getNumSubscribers() 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)
image_transport::Publisher pub
void convYCbCr411toQuadRGB(uint8_t rgb[12], const uint8_t *row, int i)
static const int ComponentIntensity
ImagePublisher(image_transport::ImageTransport &it, const std::string &frame_id, bool left, bool color, bool out1_filter, std::function< void()> &sub_changed)
void * getBase(std::uint32_t part) const
void publish(const sensor_msgs::Image &message) const
std::string getEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false)
uint64_t getTimestampNS() const
void subChangedIt(const image_transport::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
std::shared_ptr< GenApi::CNodeMapRef > nodemap
image_transport::Publisher pub_out1_high
size_t getHeight(std::uint32_t part) const
static const int ComponentIntensityCombined


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