camera_info_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 "camera_info_publisher.h"
35 
37 #include <rc_genicam_api/config.h>
38 
39 namespace rc
40 {
41 CameraInfoPublisher::CameraInfoPublisher(ros::NodeHandle& nh, const std::string& frame_id, bool _left,
42  std::function<void()>& sub_changed)
43  : GenICam2RosPublisher(frame_id)
44 {
45  // prepare camera info message
46 
47  info.header.frame_id = frame_id;
48 
49  info.width = 0;
50  info.height = 0;
51  info.distortion_model = "plumb_bob"; // we have to choose a model
52  info.D.resize(5); // all 0, since images are rectified
53 
54  info.K[0] = 1;
55  info.K[1] = 0;
56  info.K[2] = 0;
57  info.K[3] = 0;
58  info.K[4] = 1;
59  info.K[5] = 0;
60  info.K[6] = 0;
61  info.K[7] = 0;
62  info.K[8] = 1;
63 
64  info.R[0] = 1;
65  info.R[1] = 0;
66  info.R[2] = 0;
67  info.R[3] = 0;
68  info.R[4] = 1;
69  info.R[5] = 0;
70  info.R[6] = 0;
71  info.R[7] = 0;
72  info.R[8] = 1;
73 
74  info.P[0] = 1;
75  info.P[1] = 0;
76  info.P[2] = 0;
77  info.P[3] = 0;
78  info.P[4] = 0;
79  info.P[5] = 1;
80  info.P[6] = 0;
81  info.P[7] = 0;
82  info.P[8] = 0;
83  info.P[9] = 0;
84  info.P[10] = 1;
85  info.P[11] = 0;
86 
87  info.binning_x = 1;
88  info.binning_y = 1;
89 
90  // advertise topic
91 
92  left = _left;
93 
94  if (left)
95  {
96  sub_callback = sub_changed;
97  pub = nh.advertise<sensor_msgs::CameraInfo>("left/camera_info", 1,
98  boost::bind(&GenICam2RosPublisher::subChanged, this, _1),
99  boost::bind(&GenICam2RosPublisher::subChanged, this, _1));
100  left = true;
101  }
102  else
103  {
104  sub_callback = sub_changed;
105  pub = nh.advertise<sensor_msgs::CameraInfo>("right/camera_info", 1,
106  boost::bind(&GenICam2RosPublisher::subChanged, this, _1),
107  boost::bind(&GenICam2RosPublisher::subChanged, this, _1));
108  left = false;
109  }
110 }
111 
113 {
114  return pub.getNumSubscribers() > 0;
115 }
116 
117 void CameraInfoPublisher::requiresComponents(int& components, bool& color)
118 {
119  if (pub.getNumSubscribers() > 0)
120  {
121  components |= ComponentIntensity;
122  }
123 }
124 
125 void CameraInfoPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
126 {
127  if (nodemap && pub.getNumSubscribers() > 0 && (pixelformat == Mono8 ||
128  pixelformat == YCbCr411_8 || pixelformat == RGB8))
129  {
130  uint64_t time = buffer->getTimestampNS();
131 
132  info.header.seq++;
133  info.header.stamp.sec = time / 1000000000ul;
134  info.header.stamp.nsec = time % 1000000000ul;
135 
136  info.width = static_cast<uint32_t>(buffer->getWidth(part));
137  info.height = static_cast<uint32_t>(buffer->getHeight(part));
138 
139  if (info.height > info.width)
140  {
141  info.height >>= 1; // left and right images are stacked together
142  rcg::setEnum(nodemap, "ChunkComponentSelector", "IntensityCombined", false);
143  }
144  else
145  {
146  rcg::setEnum(nodemap, "ChunkComponentSelector", "Intensity", true);
147  }
148 
149  double f = rcg::getFloat(nodemap, "ChunkScan3dFocalLength", 0, 0, true);
150  double t = rcg::getFloat(nodemap, "ChunkScan3dBaseline", 0, 0, true);
151 
152  info.K[0] = info.K[4] = f;
153  info.P[0] = info.P[5] = f;
154 
155  info.P[2] = info.K[2] = rcg::getFloat(nodemap, "ChunkScan3dPrincipalPointU", 0, 0, true);
156  info.P[6] = info.K[5] = rcg::getFloat(nodemap, "ChunkScan3dPrincipalPointV", 0, 0, true);
157 
158  if (left)
159  {
160  info.P[3] = 0;
161  }
162  else
163  {
164  info.P[3] = -f * t;
165  }
166 
167  pub.publish(info);
168  }
169 }
170 
171 } // namespace rc
Interface for all publishers relating to images, point clouds or other stereo-camera data...
Mono8
f
std::function< void()> sub_callback
size_t getWidth(std::uint32_t part) const
YCbCr411_8
bool setEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception=false)
static const int ComponentIntensity
void subChanged(const ros::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
CameraInfoPublisher(ros::NodeHandle &nh, const std::string &frame_id, bool left, std::function< void()> &sub_changed)
Initialization of publisher.
void publish(const boost::shared_ptr< M > &message) const
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.
size_t getHeight(std::uint32_t part) const
RGB8
uint64_t getTimestampNS() const
bool used() override
Returns true if there are subscribers to the topic.
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)
sensor_msgs::CameraInfo info
std::shared_ptr< GenApi::CNodeMapRef > nodemap
uint32_t getNumSubscribers() const
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.


rc_genicam_driver
Author(s): Heiko Hirschmueller , Felix Ruess
autogenerated on Sun Mar 12 2023 02:20:15