Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
camera1394stereo::Camera1394Stereo Class Reference

#include <dev_camera1394stereo.h>

Public Member Functions

 Camera1394Stereo ()
 
bool checkCameraInfo (const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &ci)
 
int close ()
 
int open (camera1394stereo::Camera1394StereoConfig &newconfig)
 
bool readData (sensor_msgs::Image &image, sensor_msgs::Image &image2)
 
void setOperationalParameters (sensor_msgs::CameraInfo &ci)
 
 ~Camera1394Stereo ()
 

Public Attributes

std::string device_id_
 
boost::shared_ptr< Featuresfeatures_
 

Private Member Functions

bool findBayerMethod (const char *)
 
void findBayerPattern (const char *)
 
bool findStereoMethod (const char *method)
 
void SafeCleanup ()
 

Private Attributes

dc1394bayer_method_t BayerMethod_
 
dc1394color_filter_t BayerPattern_
 
dc1394camera_t * camera_
 
dc1394color_coding_t colorCoding_
 
bool DoBayerConversion_
 
bool DoStereoExtract_
 
Format7 format7_
 
dc1394stereo_method_t stereoMethod_
 
dc1394video_mode_t videoMode_
 

Detailed Description

Definition at line 69 of file dev_camera1394stereo.h.

Constructor & Destructor Documentation

Camera1394Stereo::Camera1394Stereo ( )

Definition at line 84 of file dev_camera1394stereo.cpp.

Camera1394Stereo::~Camera1394Stereo ( )

Definition at line 88 of file dev_camera1394stereo.cpp.

Member Function Documentation

bool camera1394stereo::Camera1394Stereo::checkCameraInfo ( const sensor_msgs::Image &  image,
const sensor_msgs::CameraInfo &  ci 
)
inline

check whether CameraInfo matches current video mode

Parameters
imagecorresponding Image message
ciCameraInfo message to check
Returns
true if camera dimensions match calibration

Definition at line 85 of file dev_camera1394stereo.h.

int Camera1394Stereo::close ( )

close the 1394 device

Definition at line 390 of file dev_camera1394stereo.cpp.

bool Camera1394Stereo::findBayerMethod ( const char *  method)
private

Definition at line 120 of file dev_camera1394stereo.cpp.

void Camera1394Stereo::findBayerPattern ( const char *  bayer)
private

Definition at line 93 of file dev_camera1394stereo.cpp.

bool Camera1394Stereo::findStereoMethod ( const char *  method)
private

Definition at line 155 of file dev_camera1394stereo.cpp.

int Camera1394Stereo::open ( camera1394stereo::Camera1394StereoConfig &  newconfig)

Open the 1394 device and start streaming

Parameters
newconfignew configuration parameters
Returns
0 if successful

TODO (if successful):

  • update newconfig.guid
  • validate newconfig.video_mode
  • initialize Features class

Definition at line 184 of file dev_camera1394stereo.cpp.

bool Camera1394Stereo::readData ( sensor_msgs::Image &  image,
sensor_msgs::Image &  image2 
)

Return an image frame

Definition at line 433 of file dev_camera1394stereo.cpp.

void Camera1394Stereo::SafeCleanup ( )
private

Safe Cleanup – may get called more than once.

Definition at line 377 of file dev_camera1394stereo.cpp.

void camera1394stereo::Camera1394Stereo::setOperationalParameters ( sensor_msgs::CameraInfo &  ci)
inline

set operational parameter fields in CameraInfo message

Parameters
ciCameraInfo message to update
Postcondition
CameraInfo fields filled in (if needed): roi (region of interest) binning_x, binning_y

Definition at line 103 of file dev_camera1394stereo.h.

Member Data Documentation

dc1394bayer_method_t camera1394stereo::Camera1394Stereo::BayerMethod_
private

Definition at line 119 of file dev_camera1394stereo.h.

dc1394color_filter_t camera1394stereo::Camera1394Stereo::BayerPattern_
private

Definition at line 118 of file dev_camera1394stereo.h.

dc1394camera_t* camera1394stereo::Camera1394Stereo::camera_
private

Definition at line 115 of file dev_camera1394stereo.h.

dc1394color_coding_t camera1394stereo::Camera1394Stereo::colorCoding_
private

Definition at line 117 of file dev_camera1394stereo.h.

std::string camera1394stereo::Camera1394Stereo::device_id_

Definition at line 109 of file dev_camera1394stereo.h.

bool camera1394stereo::Camera1394Stereo::DoBayerConversion_
private

Definition at line 120 of file dev_camera1394stereo.h.

bool camera1394stereo::Camera1394Stereo::DoStereoExtract_
private

Definition at line 122 of file dev_camera1394stereo.h.

boost::shared_ptr<Features> camera1394stereo::Camera1394Stereo::features_

Definition at line 110 of file dev_camera1394stereo.h.

Format7 camera1394stereo::Camera1394Stereo::format7_
private

Definition at line 123 of file dev_camera1394stereo.h.

dc1394stereo_method_t camera1394stereo::Camera1394Stereo::stereoMethod_
private

Definition at line 121 of file dev_camera1394stereo.h.

dc1394video_mode_t camera1394stereo::Camera1394Stereo::videoMode_
private

Definition at line 116 of file dev_camera1394stereo.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