#include <driver1394.h>
Public Member Functions | |
Camera1394Driver (ros::NodeHandle priv_nh, ros::NodeHandle camera_nh) | |
void | poll (void) |
void | setup (void) |
void | shutdown (void) |
~Camera1394Driver () | |
Static Public Attributes | |
static const uint8_t | CLOSED = 0 |
static const uint8_t | OPENED = 1 |
static const uint8_t | RUNNING = 2 |
Private Member Functions | |
void | closeCamera () |
bool | getCameraRegisters (camera1394::GetCameraRegisters::Request &request, camera1394::GetCameraRegisters::Response &response) |
bool | openCamera (Config &newconfig) |
void | publish (const sensor_msgs::ImagePtr &image) |
bool | read (sensor_msgs::ImagePtr &image) |
void | reconfig (camera1394::Camera1394Config &newconfig, uint32_t level) |
bool | setCameraRegisters (camera1394::SetCameraRegisters::Request &request, camera1394::SetCameraRegisters::Response &response) |
Private Attributes | |
bool | calibration_matches_ |
std::string | camera_name_ |
ros::NodeHandle | camera_nh_ |
boost::shared_ptr < camera_info_manager::CameraInfoManager > | cinfo_ |
camera1394::Camera1394Config | config_ |
uint32_t | consecutive_read_errors_ |
ros::Rate | cycle_ |
boost::shared_ptr < camera1394::Camera1394 > | dev_ |
diagnostic_updater::Updater | diagnostics_ |
ros::ServiceServer | get_camera_registers_srv_ |
image_transport::CameraPublisher | image_pub_ |
boost::shared_ptr < image_transport::ImageTransport > | it_ |
boost::mutex | mutex_ |
ros::NodeHandle | priv_nh_ |
volatile bool | reconfiguring_ |
uint32_t | retries_ |
ros::ServiceServer | set_camera_registers_srv_ |
dynamic_reconfigure::Server < camera1394::Camera1394Config > | srv_ |
volatile uint8_t | state_ |
diagnostic_updater::TopicDiagnostic | topic_diagnostics_ |
double | topic_diagnostics_max_freq_ |
double | topic_diagnostics_min_freq_ |
Definition at line 75 of file driver1394.h.
camera1394_driver::Camera1394Driver::Camera1394Driver | ( | ros::NodeHandle | priv_nh, |
ros::NodeHandle | camera_nh | ||
) |
Definition at line 67 of file driver1394.cpp.
Definition at line 99 of file driver1394.cpp.
void camera1394_driver::Camera1394Driver::closeCamera | ( | ) | [private] |
Close camera device
postcondition: state_ is Driver::CLOSED
Definition at line 106 of file driver1394.cpp.
bool camera1394_driver::Camera1394Driver::getCameraRegisters | ( | camera1394::GetCameraRegisters::Request & | request, |
camera1394::GetCameraRegisters::Response & | response | ||
) | [private] |
Callback for getting camera control and status registers (CSR)
Definition at line 407 of file driver1394.cpp.
bool camera1394_driver::Camera1394Driver::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 128 of file driver1394.cpp.
void camera1394_driver::Camera1394Driver::poll | ( | void | ) |
device poll
Definition at line 183 of file driver1394.cpp.
void camera1394_driver::Camera1394Driver::publish | ( | const sensor_msgs::ImagePtr & | image | ) | [private] |
Publish camera stream topics
image | points to latest camera frame |
Definition at line 235 of file driver1394.cpp.
bool camera1394_driver::Camera1394Driver::read | ( | sensor_msgs::ImagePtr & | image | ) | [private] |
Read camera data.
image | points to camera Image message |
Definition at line 288 of file driver1394.cpp.
void camera1394_driver::Camera1394Driver::reconfig | ( | camera1394::Camera1394Config & | 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 316 of file driver1394.cpp.
bool camera1394_driver::Camera1394Driver::setCameraRegisters | ( | camera1394::SetCameraRegisters::Request & | request, |
camera1394::SetCameraRegisters::Response & | response | ||
) | [private] |
Callback for setting camera control and status registers (CSR)
Definition at line 467 of file driver1394.cpp.
void camera1394_driver::Camera1394Driver::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 394 of file driver1394.cpp.
void camera1394_driver::Camera1394Driver::shutdown | ( | void | ) |
driver termination
Definition at line 401 of file driver1394.cpp.
bool camera1394_driver::Camera1394Driver::calibration_matches_ [private] |
Definition at line 128 of file driver1394.h.
std::string camera1394_driver::Camera1394Driver::camera_name_ [private] |
Definition at line 114 of file driver1394.h.
Definition at line 113 of file driver1394.h.
boost::shared_ptr<camera_info_manager::CameraInfoManager> camera1394_driver::Camera1394Driver::cinfo_ [private] |
camera calibration information
Definition at line 127 of file driver1394.h.
const uint8_t camera1394_driver::Camera1394Driver::CLOSED = 0 [static] |
Definition at line 80 of file driver1394.h.
camera1394::Camera1394Config camera1394_driver::Camera1394Driver::config_ [private] |
dynamic parameter configuration
Definition at line 123 of file driver1394.h.
uint32_t camera1394_driver::Camera1394Driver::consecutive_read_errors_ [private] |
Definition at line 117 of file driver1394.h.
Definition at line 115 of file driver1394.h.
boost::shared_ptr<camera1394::Camera1394> camera1394_driver::Camera1394Driver::dev_ [private] |
libdc1394 camera device interface
Definition at line 120 of file driver1394.h.
diagnostics updater
Definition at line 139 of file driver1394.h.
services for getting/setting camera control and status registers (CSR)
Definition at line 135 of file driver1394.h.
Definition at line 132 of file driver1394.h.
boost::shared_ptr<image_transport::ImageTransport> camera1394_driver::Camera1394Driver::it_ [private] |
image transport interfaces
Definition at line 131 of file driver1394.h.
boost::mutex camera1394_driver::Camera1394Driver::mutex_ [private] |
Non-recursive mutex for serializing callbacks with device polling.
Definition at line 107 of file driver1394.h.
const uint8_t camera1394_driver::Camera1394Driver::OPENED = 1 [static] |
Definition at line 81 of file driver1394.h.
Definition at line 112 of file driver1394.h.
volatile bool camera1394_driver::Camera1394Driver::reconfiguring_ [private] |
Definition at line 111 of file driver1394.h.
uint32_t camera1394_driver::Camera1394Driver::retries_ [private] |
Definition at line 116 of file driver1394.h.
const uint8_t camera1394_driver::Camera1394Driver::RUNNING = 2 [static] |
Definition at line 82 of file driver1394.h.
Definition at line 136 of file driver1394.h.
dynamic_reconfigure::Server<camera1394::Camera1394Config> camera1394_driver::Camera1394Driver::srv_ [private] |
Definition at line 124 of file driver1394.h.
volatile uint8_t camera1394_driver::Camera1394Driver::state_ [private] |
driver state variables
Definition at line 110 of file driver1394.h.
diagnostic_updater::TopicDiagnostic camera1394_driver::Camera1394Driver::topic_diagnostics_ [private] |
Definition at line 142 of file driver1394.h.
double camera1394_driver::Camera1394Driver::topic_diagnostics_max_freq_ [private] |
Definition at line 141 of file driver1394.h.
double camera1394_driver::Camera1394Driver::topic_diagnostics_min_freq_ [private] |
Definition at line 140 of file driver1394.h.