Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes
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 ()

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_

Detailed Description

Definition at line 75 of file driver1394.h.


Constructor & Destructor Documentation

Definition at line 67 of file driver1394.cpp.

Definition at line 99 of file driver1394.cpp.


Member Function Documentation

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.

Open the camera device.

Parameters:
newconfigconfiguration parameters
Returns:
true, if successful
Postcondition:
diagnostics frequency parameters set

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

Definition at line 128 of file driver1394.cpp.

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

Parameters:
imagepoints 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.

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

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.

Parameters:
newconfignew Config values
levelbit-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.

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.

driver termination

Definition at line 401 of file driver1394.cpp.


Member Data Documentation

Definition at line 128 of file driver1394.h.

Definition at line 114 of file driver1394.h.

Definition at line 113 of file driver1394.h.

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.

Definition at line 117 of file driver1394.h.

Definition at line 115 of file driver1394.h.

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.

image transport interfaces

Definition at line 131 of file driver1394.h.

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.

Definition at line 111 of file driver1394.h.

Definition at line 116 of file driver1394.h.

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.

Definition at line 142 of file driver1394.h.

Definition at line 141 of file driver1394.h.

Definition at line 140 of file driver1394.h.


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


camera1394
Author(s): Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy
autogenerated on Thu Jun 6 2019 19:34:17