camera_info_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 "camera_info_publisher.h"
35 
37 
38 namespace rc
39 {
40 CameraInfoPublisher::CameraInfoPublisher(ros::NodeHandle& nh, const std::string& frame_id_prefix,
41  double _f, double t, bool left)
42  : GenICam2RosPublisher(frame_id_prefix)
43 {
44  f = _f;
45 
46  // prepare camera info message
47 
48  info.header.frame_id = frame_id;
49 
50  info.width = 0;
51  info.height = 0;
52  info.distortion_model = "plumb_bob"; // we have to choose a model
53  info.D.resize(5); // all 0, since images are rectified
54 
55  info.K[0] = 1;
56  info.K[1] = 0;
57  info.K[2] = 0;
58  info.K[3] = 0;
59  info.K[4] = 1;
60  info.K[5] = 0;
61  info.K[6] = 0;
62  info.K[7] = 0;
63  info.K[8] = 1;
64 
65  info.R[0] = 1;
66  info.R[1] = 0;
67  info.R[2] = 0;
68  info.R[3] = 0;
69  info.R[4] = 1;
70  info.R[5] = 0;
71  info.R[6] = 0;
72  info.R[7] = 0;
73  info.R[8] = 1;
74 
75  info.P[0] = 1;
76  info.P[1] = 0;
77  info.P[2] = 0;
78  info.P[3] = 0;
79  info.P[4] = 0;
80  info.P[5] = 1;
81  info.P[6] = 0;
82  info.P[7] = 0;
83  info.P[8] = 0;
84  info.P[9] = 0;
85  info.P[10] = 1;
86  info.P[11] = 0;
87 
88  info.binning_x = 1;
89  info.binning_y = 1;
90 
91  // advertise topic
92 
93  if (left)
94  {
95  pub = nh.advertise<sensor_msgs::CameraInfo>("left/camera_info", 1);
96  p3_factor = 0;
97  }
98  else
99  {
100  pub = nh.advertise<sensor_msgs::CameraInfo>("right/camera_info", 1);
101  p3_factor = -f * t;
102  }
103 }
104 
106 {
107  return pub.getNumSubscribers() > 0;
108 }
109 
110 void CameraInfoPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
111 {
112  if (pub.getNumSubscribers() > 0 && (pixelformat == Mono8 || pixelformat == YCbCr411_8))
113  {
114  const uint64_t freq = 1000000000ul;
115  uint64_t time = buffer->getTimestampNS();
116 
117  info.header.seq++;
118  info.header.stamp.sec = time / freq;
119  info.header.stamp.nsec = time - freq * info.header.stamp.sec;
120 
121  info.width = static_cast<uint32_t>(buffer->getWidth(part));
122  info.height = static_cast<uint32_t>(buffer->getHeight(part));
123 
124  if (info.height > info.width)
125  {
126  info.height >>= 1; // left and right images are stacked together
127  }
128 
129  info.K[0] = info.K[4] = f * info.width;
130  info.P[0] = info.P[5] = f * info.width;
131 
132  info.P[2] = info.K[2] = info.width / 2.0;
133  info.P[6] = info.K[5] = info.height / 2.0;
134 
135  info.P[3] = p3_factor * info.width;
136 
137  pub.publish(info);
138  }
139 }
140 }
Interface for all publishers relating to images, point clouds or other stereo-camera data...
void publish(const boost::shared_ptr< M > &message) const
Mono8
YCbCr411_8
size_t getWidth(std::uint32_t part) 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)
uint64_t getTimestampNS() const
uint32_t getNumSubscribers() const
sensor_msgs::CameraInfo info
size_t getHeight(std::uint32_t part) const
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
CameraInfoPublisher(ros::NodeHandle &nh, const std::string &frame_id_prefix, double f, double t, bool left)
Initialization of publisher.


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Sat Feb 13 2021 03:42:55