#include <naoqi_camera.h>
Definition at line 79 of file naoqi_camera.h.
naoqicamera_driver::NaoqiCameraDriver::NaoqiCameraDriver | ( | int | argc, |
char ** | argv, | ||
ros::NodeHandle | priv_nh, | ||
ros::NodeHandle | camera_nh | ||
) |
Definition at line 89 of file naoqi_camera.cpp.
Definition at line 133 of file naoqi_camera.cpp.
void naoqicamera_driver::NaoqiCameraDriver::closeCamera | ( | ) | [private] |
Close camera device
postcondition: state_ is Driver::CLOSED
Definition at line 162 of file naoqi_camera.cpp.
void naoqicamera_driver::NaoqiCameraDriver::getNaoqiParams | ( | ros::NodeHandle | nh | ) | [private] |
Get broker ip and port from ROS parameters.
nh | Nodehandle used to get parameters |
Definition at line 141 of file naoqi_camera.cpp.
bool naoqicamera_driver::NaoqiCameraDriver::openCamera | ( | Config & | newconfig | ) | [private] |
Open the camera device.
newconfig | configuration parameters |
if successful: state_ is Driver::OPENED camera_name_ set to GUID string GUID configuration parameter updated
Definition at line 184 of file naoqi_camera.cpp.
void naoqicamera_driver::NaoqiCameraDriver::poll | ( | void | ) |
device poll
Definition at line 251 of file naoqi_camera.cpp.
void naoqicamera_driver::NaoqiCameraDriver::publish | ( | const sensor_msgs::ImagePtr & | image | ) | [private] |
Publish camera stream topics
image | points to latest camera frame |
Definition at line 307 of file naoqi_camera.cpp.
bool naoqicamera_driver::NaoqiCameraDriver::read | ( | sensor_msgs::ImagePtr & | image | ) | [private] |
Read camera data.
image | points to camera Image message |
Definition at line 359 of file naoqi_camera.cpp.
void naoqicamera_driver::NaoqiCameraDriver::reconfig | ( | naoqicamera::NaoqiCameraConfig & | newconfig, |
uint32_t | level | ||
) | [private] |
Dynamic reconfigure callback
Called immediately when callback first defined. Called again when dynamic reconfigure starts or changes a parameter value.
newconfig | new Config values |
level | bit-wise OR of reconfiguration levels for all changed parameters (0xffffffff on initial call) |
Definition at line 414 of file naoqi_camera.cpp.
void naoqicamera_driver::NaoqiCameraDriver::setup | ( | void | ) |
driver initialization
Define dynamic reconfigure callback, which gets called immediately with level 0xffffffff. The reconfig() method will set initial parameter values, then open the device if it can.
Definition at line 518 of file naoqi_camera.cpp.
void naoqicamera_driver::NaoqiCameraDriver::shutdown | ( | void | ) |
driver termination
Definition at line 526 of file naoqi_camera.cpp.
bool naoqicamera_driver::NaoqiCameraDriver::calibration_matches_ [private] |
Definition at line 124 of file naoqi_camera.h.
std::string naoqicamera_driver::NaoqiCameraDriver::camera_name_ [private] |
Definition at line 108 of file naoqi_camera.h.
Definition at line 107 of file naoqi_camera.h.
boost::shared_ptr<AL::ALVideoDeviceProxy> naoqicamera_driver::NaoqiCameraDriver::camera_proxy_ [private] |
NAOqi proxy
Definition at line 116 of file naoqi_camera.h.
boost::shared_ptr<camera_info_manager::CameraInfoManager> naoqicamera_driver::NaoqiCameraDriver::cinfo_ [private] |
camera calibration information
Definition at line 123 of file naoqi_camera.h.
naoqicamera::NaoqiCameraConfig naoqicamera_driver::NaoqiCameraDriver::config_ [private] |
dynamic parameter configuration
Definition at line 119 of file naoqi_camera.h.
Definition at line 110 of file naoqi_camera.h.
diagnostics updater
Definition at line 131 of file naoqi_camera.h.
std::string naoqicamera_driver::NaoqiCameraDriver::frame_id_ [private] |
Definition at line 109 of file naoqi_camera.h.
Definition at line 128 of file naoqi_camera.h.
boost::shared_ptr<image_transport::ImageTransport> naoqicamera_driver::NaoqiCameraDriver::it_ [private] |
image transport interfaces
Definition at line 127 of file naoqi_camera.h.
Definition at line 106 of file naoqi_camera.h.
Definition at line 111 of file naoqi_camera.h.
boost::mutex naoqicamera_driver::NaoqiCameraDriver::reconfiguration_mutex_ [private] |
Definition at line 104 of file naoqi_camera.h.
uint32_t naoqicamera_driver::NaoqiCameraDriver::retries_ [private] |
Definition at line 112 of file naoqi_camera.h.
dynamic_reconfigure::Server<naoqicamera::NaoqiCameraConfig> naoqicamera_driver::NaoqiCameraDriver::srv_ [private] |
Definition at line 120 of file naoqi_camera.h.
volatile driver_base::Driver::state_t naoqicamera_driver::NaoqiCameraDriver::state_ [private] |
driver state variables
Definition at line 103 of file naoqi_camera.h.
diagnostic_updater::TopicDiagnostic naoqicamera_driver::NaoqiCameraDriver::topic_diagnostics_ [private] |
Definition at line 134 of file naoqi_camera.h.
double naoqicamera_driver::NaoqiCameraDriver::topic_diagnostics_max_freq_ [private] |
Definition at line 133 of file naoqi_camera.h.
double naoqicamera_driver::NaoqiCameraDriver::topic_diagnostics_min_freq_ [private] |
Definition at line 132 of file naoqi_camera.h.