camera_param_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_param_publisher.h"
35 
37 #include <rc_genicam_api/config.h>
38 
39 namespace rc
40 {
41 CameraParamPublisher::CameraParamPublisher(ros::NodeHandle& nh, const std::string& frame_id, bool left,
42  std::function<void()>& sub_changed)
43  : GenICam2RosPublisher(frame_id)
44 {
45  // advertise topic
46 
47  sub_callback = sub_changed;
48 
49  if (left)
50  {
51  pub = nh.advertise<rc_common_msgs::CameraParam>("left/camera_param", 1,
52  boost::bind(&GenICam2RosPublisher::subChanged, this, _1),
53  boost::bind(&GenICam2RosPublisher::subChanged, this, _1));
54  }
55  else
56  {
57  pub = nh.advertise<rc_common_msgs::CameraParam>("right/camera_param", 1,
58  boost::bind(&GenICam2RosPublisher::subChanged, this, _1),
59  boost::bind(&GenICam2RosPublisher::subChanged, this, _1));
60  }
61 }
62 
64 {
65  return pub.getNumSubscribers() > 0;
66 }
67 
68 void CameraParamPublisher::requiresComponents(int& components, bool& color)
69 {
70  if (pub.getNumSubscribers() > 0)
71  {
72  components |= ComponentIntensity;
73  }
74 }
75 
76 namespace
77 {
78 
79 template <class T> inline rc_common_msgs::KeyValue getKeyValue(const char *key, T value)
80 {
81  rc_common_msgs::KeyValue ret;
82 
83  ret.key=key;
84  ret.value=std::to_string(value);
85 
86  return ret;
87 }
88 
89 }
90 
91 void CameraParamPublisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
92 {
93  if (nodemap && pub.getNumSubscribers() > 0 && (pixelformat == Mono8 || pixelformat == YCbCr411_8))
94  {
95  uint64_t time = buffer->getTimestampNS();
96 
97  rc_common_msgs::CameraParam param;
98 
99  param.header.frame_id = frame_id;
100  param.header.stamp.sec = time / 1000000000ul;
101  param.header.stamp.nsec = time % 1000000000ul;
102 
103  // get list of all available IO lines and iterate over them to get their
104  // LineSource values
105 
106  std::vector<std::string> lines;
107  rcg::getEnum(nodemap, "ChunkLineSelector", lines, true);
108  for (auto&& line : lines)
109  {
110  rcg::setEnum(nodemap, "ChunkLineSelector", line.c_str(), true);
111 
112  rc_common_msgs::KeyValue line_source;
113  line_source.key = line;
114  line_source.value = rcg::getEnum(nodemap, "ChunkLineSource", true);
115 
116  param.line_source.push_back(line_source);
117  }
118 
119  param.line_status_all = rcg::getInteger(nodemap, "ChunkLineStatusAll", 0, 0, true);
120 
121  param.gain = rcg::getFloat(nodemap, "ChunkGain", 0, 0, true);
122  param.exposure_time = rcg::getFloat(nodemap, "ChunkExposureTime", 0, 0, true) / 1000000l;
123 
124  {
125  float noise=rcg::getFloat(nodemap, "ChunkRcNoise", 0, 0, false);
126  bool test=rcg::getBoolean(nodemap, "ChunkRcTest", false);
127 
128  float out1_reduction=0;
129 
130  try
131  {
132  out1_reduction=rcg::getFloat(nodemap, "ChunkRcOut1Reduction", 0, 0, true);
133  }
134  catch (const std::exception &)
135  {
136  // can be removed if sensor version must be >= 20.10.1
137  out1_reduction=rcg::getFloat(nodemap, "ChunkRcAdaptiveOut1Reduction", 0, 0, false);
138  }
139 
140  float brightness=rcg::getFloat(nodemap, "ChunkRcBrightness", 0, 0, false);
141 
142  param.extra_data.clear();
143  param.extra_data.push_back(getKeyValue("noise", noise));
144  param.extra_data.push_back(getKeyValue("test", test));
145  param.extra_data.push_back(getKeyValue("out1_reduction", out1_reduction));
146  param.extra_data.push_back(getKeyValue("brightness", brightness));
147  }
148 
149  pub.publish(param);
150  }
151 }
152 
153 } // 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.
bool getBoolean(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false, bool igncache=false)
bool param(const std::string &param_name, T &param_val, const T &default_val)
bool used() override
Returns true if there are subscribers to the topic.
void publish(const boost::shared_ptr< M > &message) const
Mono8
std::function< void()> sub_callback
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)
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.
std::string getEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false)
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)
uint64_t getTimestampNS() const
uint32_t getNumSubscribers() const
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
CameraParamPublisher(ros::NodeHandle &nh, const std::string &frame_id, bool left, std::function< void()> &sub_changed)
std::shared_ptr< GenApi::CNodeMapRef > nodemap


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