Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes
camera1394stereo_driver::Camera1394StereoDriver Class Reference

#include <driver1394stereo.h>

List of all members.

Public Member Functions

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

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::CameraInfoManager
cinfo_ [NUM_CAMERAS]
camera1394stereo::Camera1394StereoConfig config_
ros::Rate cycle_
boost::shared_ptr
< camera1394stereo::Camera1394Stereo
dev_
image_transport::CameraPublisher image_pub_ [NUM_CAMERAS]
boost::shared_ptr
< image_transport::ImageTransport
it_
boost::mutex mutex_
ros::NodeHandle priv_nh_
volatile bool reconfiguring_
ros::NodeHandle single_camera_nh_ [NUM_CAMERAS]
dynamic_reconfigure::Server
< camera1394stereo::Camera1394StereoConfig > 
srv_
volatile
driver_base::Driver::state_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 60 of file driver1394stereo.h.


Member Enumeration Documentation

Enumerator:
LEFT 
RIGHT 

Definition at line 74 of file driver1394stereo.h.


Constructor & Destructor Documentation

Definition at line 80 of file driver1394stereo.cpp.

Definition at line 101 of file driver1394stereo.cpp.


Member Function Documentation

Close camera device

postcondition: state_ is Driver::CLOSED

Definition at line 108 of file driver1394stereo.cpp.

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 127 of file driver1394stereo.cpp.

device poll

Definition at line 188 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 227 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 283 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 311 of file driver1394stereo.cpp.

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 406 of file driver1394stereo.cpp.

driver termination

Definition at line 413 of file driver1394stereo.cpp.


Member Data Documentation

Definition at line 106 of file driver1394stereo.h.

Definition at line 94 of file driver1394stereo.h.

Definition at line 92 of file driver1394stereo.h.

const std::string camera1394stereo_driver::Camera1394StereoDriver::CameraSelectorString = {"left","right"} [static, private]

Definition at line 76 of file driver1394stereo.h.

camera calibration information

Definition at line 105 of file driver1394stereo.h.

camera1394stereo::Camera1394StereoConfig camera1394stereo_driver::Camera1394StereoDriver::config_ [private]

dynamic parameter configuration

Definition at line 100 of file driver1394stereo.h.

Definition at line 102 of file driver1394stereo.h.

libdc1394 camera device interface

Definition at line 97 of file driver1394stereo.h.

Definition at line 110 of file driver1394stereo.h.

image transport interfaces

Definition at line 109 of file driver1394stereo.h.

Non-recursive mutex for serializing callbacks with device polling.

Definition at line 86 of file driver1394stereo.h.

Definition at line 75 of file driver1394stereo.h.

Definition at line 91 of file driver1394stereo.h.

Definition at line 89 of file driver1394stereo.h.

Definition at line 93 of file driver1394stereo.h.

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

Definition at line 101 of file driver1394stereo.h.

Definition at line 88 of file driver1394stereo.h.


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


camera1394stereo
Author(s): Joan Pau Beltran
autogenerated on Sun Oct 5 2014 22:44:07