publishers/camera.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef PUBLISHER_CAMERA_HPP
19 #define PUBLISHER_CAMERA_HPP
20 
21 /*
22 * ROS includes
23 */
24 #include <ros/ros.h>
26 
27 namespace naoqi
28 {
29 namespace publisher
30 {
31 
33 {
34 public:
35  CameraPublisher( const std::string& topic, int camera_source );
36 
38 
39  inline std::string topic() const
40  {
41  return topic_;
42  }
43 
44  inline bool isInitialized() const
45  {
46  return is_initialized_;
47  }
48 
49  void publish( const sensor_msgs::ImagePtr& img, const sensor_msgs::CameraInfo& camera_info );
50 
51  void reset( ros::NodeHandle& nh );
52 
53  inline bool isSubscribed() const
54  {
55  if (is_initialized_ == false) return false;
56  return pub_.getNumSubscribers() > 0;
57  }
58 
59 private:
60  std::string topic_;
61 
63 
64  //image_transport::ImageTransport it_;
66 
68 };
69 
70 } //publisher
71 } //naoqi
72 
73 
74 #endif
naoqi::publisher::CameraPublisher
Definition: publishers/camera.hpp:32
image_transport::CameraPublisher::getNumSubscribers
uint32_t getNumSubscribers() const
ros.h
naoqi::publisher::CameraPublisher::~CameraPublisher
~CameraPublisher()
Definition: publishers/camera.cpp:40
naoqi
Definition: converter.hpp:29
naoqi::publisher::CameraPublisher::publish
void publish(const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
Definition: publishers/camera.cpp:44
naoqi::publisher::CameraPublisher::is_initialized_
bool is_initialized_
Definition: publishers/camera.hpp:62
naoqi::publisher::CameraPublisher::topic
std::string topic() const
Definition: publishers/camera.hpp:39
image_transport::CameraPublisher
image_transport.h
naoqi::publisher::CameraPublisher::camera_source_
int camera_source_
Definition: publishers/camera.hpp:67
naoqi::publisher::CameraPublisher::isSubscribed
bool isSubscribed() const
Definition: publishers/camera.hpp:53
naoqi::publisher::CameraPublisher::topic_
std::string topic_
Definition: publishers/camera.hpp:60
naoqi::publisher::CameraPublisher::pub_
image_transport::CameraPublisher pub_
Definition: publishers/camera.hpp:65
naoqi::publisher::CameraPublisher::CameraPublisher
CameraPublisher(const std::string &topic, int camera_source)
Definition: publishers/camera.cpp:33
naoqi::publisher::CameraPublisher::reset
void reset(ros::NodeHandle &nh)
Definition: publishers/camera.cpp:49
ros::NodeHandle
naoqi::publisher::CameraPublisher::isInitialized
bool isInitialized() const
Definition: publishers/camera.hpp:44


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06