$search

camera1394_driver::Camera1394Driver Class Reference

#include <driver1394.h>

List of all members.

Public Member Functions

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

Private Member Functions

void closeCamera ()
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)

Private Attributes

bool calibration_matches_
std::string camera_name_
ros::NodeHandle camera_nh_
boost::shared_ptr
< camera_info_manager::CameraInfoManager
cinfo_
camera1394::Camera1394Config config_
ros::Rate cycle_
boost::shared_ptr
< camera1394::Camera1394
dev_
image_transport::CameraPublisher image_pub_
boost::shared_ptr
< image_transport::ImageTransport
it_
boost::mutex mutex_
ros::NodeHandle priv_nh_
volatile bool reconfiguring_
dynamic_reconfigure::Server
< camera1394::Camera1394Config > 
srv_
volatile
driver_base::Driver::state_t 
state_

Detailed Description

Definition at line 60 of file driver1394.h.


Constructor & Destructor Documentation

camera1394_driver::Camera1394Driver::Camera1394Driver ( ros::NodeHandle  priv_nh,
ros::NodeHandle  camera_nh 
)

Definition at line 71 of file driver1394.cpp.

camera1394_driver::Camera1394Driver::~Camera1394Driver (  ) 

Definition at line 87 of file driver1394.cpp.


Member Function Documentation

void camera1394_driver::Camera1394Driver::closeCamera (  )  [private]

Close camera device

postcondition: state_ is Driver::CLOSED

Definition at line 94 of file driver1394.cpp.

bool camera1394_driver::Camera1394Driver::openCamera ( Config newconfig  )  [private]

Open the camera device.

Parameters:
newconfig configuration parameters
Returns:
true, if successful

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

Definition at line 113 of file driver1394.cpp.

void camera1394_driver::Camera1394Driver::poll ( void   ) 

device poll

Definition at line 164 of file driver1394.cpp.

void camera1394_driver::Camera1394Driver::publish ( const sensor_msgs::ImagePtr image  )  [private]

Publish camera stream topics

Parameters:
image points to latest camera frame

Definition at line 201 of file driver1394.cpp.

bool camera1394_driver::Camera1394Driver::read ( sensor_msgs::ImagePtr image  )  [private]

Read camera data.

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

Definition at line 252 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.

Parameters:
newconfig new Config values
level bit-wise OR of reconfiguration levels for all changed parameters (0xffffffff on initial call)

Definition at line 280 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 362 of file driver1394.cpp.

void camera1394_driver::Camera1394Driver::shutdown ( void   ) 

driver termination

Definition at line 369 of file driver1394.cpp.


Member Data Documentation

Definition at line 101 of file driver1394.h.

Definition at line 89 of file driver1394.h.

Definition at line 88 of file driver1394.h.

camera calibration information

Definition at line 100 of file driver1394.h.

camera1394::Camera1394Config camera1394_driver::Camera1394Driver::config_ [private]

dynamic parameter configuration

Definition at line 95 of file driver1394.h.

Definition at line 97 of file driver1394.h.

libdc1394 camera device interface

Definition at line 92 of file driver1394.h.

Definition at line 105 of file driver1394.h.

image transport interfaces

Definition at line 104 of file driver1394.h.

Non-recursive mutex for serializing callbacks with device polling.

Definition at line 82 of file driver1394.h.

Definition at line 87 of file driver1394.h.

Definition at line 85 of file driver1394.h.

dynamic_reconfigure::Server<camera1394::Camera1394Config> camera1394_driver::Camera1394Driver::srv_ [private]

Definition at line 96 of file driver1394.h.

Definition at line 84 of file driver1394.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


camera1394
Author(s): Jack O'Quin, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy, Ken Tossell
autogenerated on Sat Mar 2 12:11:29 2013