Public Member Functions | Static Public Attributes | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
camera1394stereo_driver::Camera1394StereoDriver Class Reference

#include <driver1394stereo.h>

Public Member Functions

 Camera1394StereoDriver (ros::NodeHandle priv_nh, ros::NodeHandle camera_nh)
 
void poll (void)
 
void setup (void)
 
void shutdown (void)
 
 ~Camera1394StereoDriver ()
 

Static Public Attributes

static const uint8_t CLOSED = 0
 
static const uint8_t OPENED = 1
 
static const uint8_t RUNNING = 2
 

Private Types

enum  CameraSelector { LEFT =0, RIGHT =1 }
 

Private Member Functions

void closeCamera ()
 
bool openCamera (Config &newconfig)
 
void publish (const sensor_msgs::ImagePtr image[NUM_CAMERAS])
 
bool read (sensor_msgs::ImagePtr image[NUM_CAMERAS])
 
void reconfig (camera1394stereo::Camera1394StereoConfig &newconfig, uint32_t level)
 

Private Attributes

bool calibration_matches_ [NUM_CAMERAS]
 
std::string camera_name_
 
ros::NodeHandle camera_nh_
 
boost::shared_ptr< camera_info_manager::CameraInfoManagercinfo_ [NUM_CAMERAS]
 
camera1394stereo::Camera1394StereoConfig config_
 
ros::Rate cycle_
 
boost::shared_ptr< camera1394stereo::Camera1394Stereodev_
 
image_transport::CameraPublisher image_pub_ [NUM_CAMERAS]
 
boost::shared_ptr< image_transport::ImageTransportit_
 
boost::mutex mutex_
 
ros::NodeHandle priv_nh_
 
volatile bool reconfiguring_
 
ros::NodeHandle single_camera_nh_ [NUM_CAMERAS]
 
dynamic_reconfigure::Server< camera1394stereo::Camera1394StereoConfig > srv_
 
volatile uint8_t state_
 

Static Private Attributes

static const std::string CameraSelectorString [NUM_CAMERAS] = {"left","right"}
 
static const int NUM_CAMERAS = 2
 

Detailed Description

Definition at line 70 of file driver1394stereo.h.

Member Enumeration Documentation

Enumerator
LEFT 
RIGHT 

Definition at line 90 of file driver1394stereo.h.

Constructor & Destructor Documentation

camera1394stereo_driver::Camera1394StereoDriver::Camera1394StereoDriver ( ros::NodeHandle  priv_nh,
ros::NodeHandle  camera_nh 
)

Definition at line 78 of file driver1394stereo.cpp.

camera1394stereo_driver::Camera1394StereoDriver::~Camera1394StereoDriver ( )

Definition at line 99 of file driver1394stereo.cpp.

Member Function Documentation

void camera1394stereo_driver::Camera1394StereoDriver::closeCamera ( )
private

Close camera device

postcondition: state_ is Driver::CLOSED

Definition at line 106 of file driver1394stereo.cpp.

bool camera1394stereo_driver::Camera1394StereoDriver::openCamera ( Config newconfig)
private

Open the camera device.

Parameters
newconfigconfiguration parameters
Returns
true, if successful

if successful: state_ is Driver::OPENED camera_name_ set to GUID string

Definition at line 125 of file driver1394stereo.cpp.

void camera1394stereo_driver::Camera1394StereoDriver::poll ( void  )

device poll

Definition at line 186 of file driver1394stereo.cpp.

void camera1394stereo_driver::Camera1394StereoDriver::publish ( const sensor_msgs::ImagePtr  image[NUM_CAMERAS])
private

Publish camera stream topics

Parameters
imagepoints to latest camera frame

Definition at line 225 of file driver1394stereo.cpp.

bool camera1394stereo_driver::Camera1394StereoDriver::read ( sensor_msgs::ImagePtr  image[NUM_CAMERAS])
private

Read camera data.

Parameters
imagepoints to camera Image message
Returns
true if successful, with image filled in

Definition at line 281 of file driver1394stereo.cpp.

void camera1394stereo_driver::Camera1394StereoDriver::reconfig ( camera1394stereo::Camera1394StereoConfig &  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.

Parameters
newconfignew Config values
levelbit-wise OR of reconfiguration levels for all changed parameters (0xffffffff on initial call)

Definition at line 309 of file driver1394stereo.cpp.

void camera1394stereo_driver::Camera1394StereoDriver::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 404 of file driver1394stereo.cpp.

void camera1394stereo_driver::Camera1394StereoDriver::shutdown ( void  )

driver termination

Definition at line 411 of file driver1394stereo.cpp.

Member Data Documentation

bool camera1394stereo_driver::Camera1394StereoDriver::calibration_matches_[NUM_CAMERAS]
private

Definition at line 122 of file driver1394stereo.h.

std::string camera1394stereo_driver::Camera1394StereoDriver::camera_name_
private

Definition at line 110 of file driver1394stereo.h.

ros::NodeHandle camera1394stereo_driver::Camera1394StereoDriver::camera_nh_
private

Definition at line 108 of file driver1394stereo.h.

const std::string camera1394stereo_driver::Camera1394StereoDriver::CameraSelectorString = {"left","right"}
staticprivate

Definition at line 92 of file driver1394stereo.h.

boost::shared_ptr<camera_info_manager::CameraInfoManager> camera1394stereo_driver::Camera1394StereoDriver::cinfo_[NUM_CAMERAS]
private

camera calibration information

Definition at line 121 of file driver1394stereo.h.

const uint8_t camera1394stereo_driver::Camera1394StereoDriver::CLOSED = 0
static

Definition at line 83 of file driver1394stereo.h.

camera1394stereo::Camera1394StereoConfig camera1394stereo_driver::Camera1394StereoDriver::config_
private

dynamic parameter configuration

Definition at line 116 of file driver1394stereo.h.

ros::Rate camera1394stereo_driver::Camera1394StereoDriver::cycle_
private

Definition at line 118 of file driver1394stereo.h.

boost::shared_ptr<camera1394stereo::Camera1394Stereo> camera1394stereo_driver::Camera1394StereoDriver::dev_
private

libdc1394 camera device interface

Definition at line 113 of file driver1394stereo.h.

image_transport::CameraPublisher camera1394stereo_driver::Camera1394StereoDriver::image_pub_[NUM_CAMERAS]
private

Definition at line 126 of file driver1394stereo.h.

boost::shared_ptr<image_transport::ImageTransport> camera1394stereo_driver::Camera1394StereoDriver::it_
private

image transport interfaces

Definition at line 125 of file driver1394stereo.h.

boost::mutex camera1394stereo_driver::Camera1394StereoDriver::mutex_
private

Non-recursive mutex for serializing callbacks with device polling.

Definition at line 102 of file driver1394stereo.h.

const int camera1394stereo_driver::Camera1394StereoDriver::NUM_CAMERAS = 2
staticprivate

Definition at line 91 of file driver1394stereo.h.

const uint8_t camera1394stereo_driver::Camera1394StereoDriver::OPENED = 1
static

Definition at line 84 of file driver1394stereo.h.

ros::NodeHandle camera1394stereo_driver::Camera1394StereoDriver::priv_nh_
private

Definition at line 107 of file driver1394stereo.h.

volatile bool camera1394stereo_driver::Camera1394StereoDriver::reconfiguring_
private

Definition at line 105 of file driver1394stereo.h.

const uint8_t camera1394stereo_driver::Camera1394StereoDriver::RUNNING = 2
static

Definition at line 85 of file driver1394stereo.h.

ros::NodeHandle camera1394stereo_driver::Camera1394StereoDriver::single_camera_nh_[NUM_CAMERAS]
private

Definition at line 109 of file driver1394stereo.h.

dynamic_reconfigure::Server<camera1394stereo::Camera1394StereoConfig> camera1394stereo_driver::Camera1394StereoDriver::srv_
private

Definition at line 117 of file driver1394stereo.h.

volatile uint8_t camera1394stereo_driver::Camera1394StereoDriver::state_
private

Definition at line 104 of file driver1394stereo.h.


The documentation for this class was generated from the following files:


camera1394stereo
Author(s): Joan Pau Beltran
autogenerated on Mon Jun 10 2019 12:52:45