camera_param_publisher.cc
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Roboception GmbH
3  * All rights reserved
4  *
5  * Author: Christian Emmerich
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 
38 namespace rc
39 {
41  const std::string& frame_id_prefix, bool left)
42  : frame_id(frame_id_prefix + "camera")
43 {
44  // advertise topic
45 
46  if (left)
47  {
48  pub = nh.advertise<rc_common_msgs::CameraParam>("left/camera_param", 1);
49  }
50  else
51  {
52  pub = nh.advertise<rc_common_msgs::CameraParam>("right/camera_param", 1);
53  }
54 }
55 
57 {
58  return pub.getNumSubscribers() > 0;
59 }
60 
61 void CameraParamPublisher::publish(const rcg::Buffer* buffer, const rc_common_msgs::CameraParam& p,
62  uint64_t pixelformat)
63 {
64  if (pub.getNumSubscribers() > 0 && (pixelformat == Mono8 || pixelformat == YCbCr411_8))
65  {
66  const uint64_t freq = 1000000000ul;
67  uint64_t time = buffer->getTimestampNS();
68 
69  // params.header.seq++;
70  auto params = p;
71  params.header.frame_id = frame_id;
72  params.header.stamp.sec = time / freq;
73  params.header.stamp.nsec = time - freq * params.header.stamp.sec;
74 
75  pub.publish(params);
76  }
77 }
78 
79 }
void publish(const rcg::Buffer *buffer, const rc_common_msgs::CameraParam &params, uint64_t pixelformat)
void publish(const boost::shared_ptr< M > &message) const
Mono8
CameraParamPublisher(ros::NodeHandle &nh, const std::string &frame_id_prefix, bool left)
YCbCr411_8
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint64_t getTimestampNS() const
uint32_t getNumSubscribers() const


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