18 #ifndef PUBLISHER_CAMERA_HPP
19 #define PUBLISHER_CAMERA_HPP
25 #include <image_transport/image_transport.h>
39 inline std::string
topic()
const
49 void publish(
const sensor_msgs::ImagePtr& img,
const sensor_msgs::CameraInfo& camera_info );
51 void reset( ros::NodeHandle& nh );
56 return pub_.getNumSubscribers() > 0;
65 image_transport::CameraPublisher
pub_;
void publish(const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
Definition: camera.cpp:44
~CameraPublisher()
Definition: camera.cpp:40
bool isInitialized() const
Definition: camera.hpp:44
image_transport::CameraPublisher pub_
Definition: camera.hpp:65
bool is_initialized_
Definition: camera.hpp:62
void reset(ros::NodeHandle &nh)
Definition: camera.cpp:49
bool isSubscribed() const
Definition: camera.hpp:53
Definition: camera.hpp:32
std::string topic() const
Definition: camera.hpp:39
CameraPublisher(const std::string &topic, int camera_source)
Definition: camera.cpp:33
int camera_source_
Definition: camera.hpp:67
std::string topic_
Definition: camera.hpp:60