error_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 
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<sensor_msgs::Image>("error_disparity", 1, boost::bind(&GenICam2RosPublisher::subChanged, this, _1),
49  boost::bind(&GenICam2RosPublisher::subChanged, this, _1));
50 }
51 
53 {
54  return pub.getNumSubscribers() > 0;
55 }
56 
57 void ErrorDisparityPublisher::requiresComponents(int& components, bool& color)
58 {
59  if (pub.getNumSubscribers() > 0)
60  {
61  components |= ComponentError;
62  }
63 }
64 
65 void ErrorDisparityPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
66 {
67  if (nodemap && pub.getNumSubscribers() > 0 && pixelformat == Error8)
68  {
69  // create image and initialize header
70 
71  sensor_msgs::ImagePtr im = boost::make_shared<sensor_msgs::Image>();
72 
73  uint64_t time = buffer->getTimestampNS();
74 
75  im->header.seq = 0;
76  im->header.stamp.sec = time / 1000000000ul;
77  im->header.stamp.nsec = time % 1000000000ul;
78  im->header.frame_id = frame_id;
79 
80  // set image size
81 
82  im->width = static_cast<uint32_t>(buffer->getWidth(part));
83  im->height = static_cast<uint32_t>(buffer->getHeight(part));
84 
85  // get pointer to image data in buffer
86 
87  size_t px = buffer->getXPadding(part);
88  const uint8_t* ps = static_cast<const uint8_t*>(buffer->getBase(part));
89 
90  // convert image data
91 
93  im->is_bigendian = rcg::isHostBigEndian();
94  im->step = im->width * sizeof(float);
95 
96  rcg::setEnum(nodemap, "ChunkComponentSelector", "Error", true);
97  float scale = rcg::getFloat(nodemap, "ChunkScan3dCoordinateScale", 0, 0, true);
98 
99  im->data.resize(im->step * im->height);
100  float* pt = reinterpret_cast<float*>(&im->data[0]);
101 
102  for (uint32_t k = 0; k < im->height; k++)
103  {
104  for (uint32_t i = 0; i < im->width; i++)
105  {
106  *pt++ = scale * *ps++;
107  }
108 
109  ps += px;
110  }
111 
112  // publish message
113 
114  pub.publish(im);
115  }
116 }
117 
118 } // namespace rc
Interface for all publishers relating to images, point clouds or other stereo-camera data...
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.
void publish(const boost::shared_ptr< M > &message) const
bool used() override
Returns true if there are subscribers to the topic.
std::function< void()> sub_callback
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
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
#define Error8
const std::string TYPE_32FC1
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ErrorDisparityPublisher(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 isHostBigEndian()
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