#include <camera.hpp>
Public Member Functions | |
| CameraPublisher (const std::string &topic, int camera_source) | |
| bool | isInitialized () const |
| bool | isSubscribed () const |
| void | publish (const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info) |
| void | reset (ros::NodeHandle &nh) |
| std::string | topic () const |
| ~CameraPublisher () | |
Private Attributes | |
| int | camera_source_ |
| bool | is_initialized_ |
| image_transport::CameraPublisher | pub_ |
| std::string | topic_ |
Definition at line 32 of file publishers/camera.hpp.
| naoqi::publisher::CameraPublisher::CameraPublisher | ( | const std::string & | topic, |
| int | camera_source | ||
| ) |
Definition at line 33 of file publishers/camera.cpp.
Definition at line 40 of file publishers/camera.cpp.
| bool naoqi::publisher::CameraPublisher::isInitialized | ( | ) | const [inline] |
Definition at line 44 of file publishers/camera.hpp.
| bool naoqi::publisher::CameraPublisher::isSubscribed | ( | ) | const [inline] |
Definition at line 53 of file publishers/camera.hpp.
| void naoqi::publisher::CameraPublisher::publish | ( | const sensor_msgs::ImagePtr & | img, |
| const sensor_msgs::CameraInfo & | camera_info | ||
| ) |
Definition at line 44 of file publishers/camera.cpp.
| void naoqi::publisher::CameraPublisher::reset | ( | ros::NodeHandle & | nh | ) |
Definition at line 49 of file publishers/camera.cpp.
| std::string naoqi::publisher::CameraPublisher::topic | ( | ) | const [inline] |
Definition at line 39 of file publishers/camera.hpp.
int naoqi::publisher::CameraPublisher::camera_source_ [private] |
Definition at line 67 of file publishers/camera.hpp.
bool naoqi::publisher::CameraPublisher::is_initialized_ [private] |
Definition at line 62 of file publishers/camera.hpp.
Definition at line 65 of file publishers/camera.hpp.
std::string naoqi::publisher::CameraPublisher::topic_ [private] |
Definition at line 60 of file publishers/camera.hpp.