camera_publisher.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * fkie_message_filters
4  * Copyright © 2018-2020 Fraunhofer FKIE
5  * Author: Timo Röhling
6  *
7  * Licensed under the Apache License, Version 2.0 (the "License");
8  * you may not use this file except in compliance with the License.
9  * You may obtain a copy of the License at
10  *
11  * http://www.apache.org/licenses/LICENSE-2.0
12  *
13  * Unless required by applicable law or agreed to in writing, software
14  * distributed under the License is distributed on an "AS IS" BASIS,
15  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16  * See the License for the specific language governing permissions and
17  * limitations under the License.
18  *
19  ****************************************************************************/
20 #ifndef INCLUDE_FKIE_MESSAGE_FILTERS_CAMERA_PUBLISHER_H_
21 #define INCLUDE_FKIE_MESSAGE_FILTERS_CAMERA_PUBLISHER_H_
22 
23 #include "publisher_base.h"
24 #include "sink.h"
25 #include <sensor_msgs/Image.h>
26 #include <sensor_msgs/CameraInfo.h>
28 
29 namespace fkie_message_filters
30 {
31 
44 class CameraPublisher : public PublisherBase, public Sink<sensor_msgs::ImageConstPtr, sensor_msgs::CameraInfoConstPtr>
45 {
46 public:
53  CameraPublisher() noexcept {}
60  CameraPublisher (const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, bool latch = false) noexcept;
65  virtual bool is_active() const noexcept override;
70  virtual std::string topic() const noexcept override;
83  void advertise (const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, bool latch = false) noexcept;
101  void advertise (const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, const image_transport::SubscriberStatusCallback& image_connect_cb, const image_transport::SubscriberStatusCallback& image_disconnect_cb = image_transport::SubscriberStatusCallback(), const ros::SubscriberStatusCallback& info_connect_cb = ros::SubscriberStatusCallback(), const ros::SubscriberStatusCallback& info_disconnect_cb = ros::SubscriberStatusCallback(), const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false) noexcept;
102 protected:
104  void receive (const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&) noexcept override;
105 private:
106  std::shared_ptr<image_transport::ImageTransport> it_;
108 };
109 
110 } // namespace fkie_message_filters
111 
112 #endif /* INCLUDE_FKIE_MESSAGE_FILTERS_CAMERA_PUBLISHER_H_ */
Base class for data consumers.
Definition: sink.h:46
void advertise(const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, bool latch=false) noexcept
Advertise ROS camera topic.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Publish consumed data to ROS camera topics.
Base class for ROS publishers in a filter pipeline.
void receive(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &) noexcept override
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::shared_ptr< image_transport::ImageTransport > it_
Primary namespace.
Definition: buffer.h:33
image_transport::CameraPublisher pub_
virtual bool is_active() const noexcept override
Check if the ROS publisher has at least one subscriber.
CameraPublisher() noexcept
Constructs an empty publisher.
virtual std::string topic() const noexcept override
Return the configured ROS topic.


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Mon Feb 28 2022 22:21:43