#include <driver1394stereo.h>
|
static const uint8_t | CLOSED = 0 |
|
static const uint8_t | OPENED = 1 |
|
static const uint8_t | RUNNING = 2 |
|
Definition at line 70 of file driver1394stereo.h.
camera1394stereo_driver::Camera1394StereoDriver::~Camera1394StereoDriver |
( |
| ) |
|
void camera1394stereo_driver::Camera1394StereoDriver::closeCamera |
( |
| ) |
|
|
private |
bool camera1394stereo_driver::Camera1394StereoDriver::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 125 of file driver1394stereo.cpp.
void camera1394stereo_driver::Camera1394StereoDriver::poll |
( |
void |
| ) |
|
void camera1394stereo_driver::Camera1394StereoDriver::publish |
( |
const sensor_msgs::ImagePtr |
image[NUM_CAMERAS] | ) |
|
|
private |
Publish camera stream topics
- Parameters
-
image | points 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
-
image | points 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
-
newconfig | new Config values |
level | bit-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 |
| ) |
|
bool camera1394stereo_driver::Camera1394StereoDriver::calibration_matches_[NUM_CAMERAS] |
|
private |
std::string camera1394stereo_driver::Camera1394StereoDriver::camera_name_ |
|
private |
ros::NodeHandle camera1394stereo_driver::Camera1394StereoDriver::camera_nh_ |
|
private |
const std::string camera1394stereo_driver::Camera1394StereoDriver::CameraSelectorString = {"left","right"} |
|
staticprivate |
const uint8_t camera1394stereo_driver::Camera1394StereoDriver::CLOSED = 0 |
|
static |
camera1394stereo::Camera1394StereoConfig camera1394stereo_driver::Camera1394StereoDriver::config_ |
|
private |
ros::Rate camera1394stereo_driver::Camera1394StereoDriver::cycle_ |
|
private |
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 |
const uint8_t camera1394stereo_driver::Camera1394StereoDriver::OPENED = 1 |
|
static |
volatile bool camera1394stereo_driver::Camera1394StereoDriver::reconfiguring_ |
|
private |
const uint8_t camera1394stereo_driver::Camera1394StereoDriver::RUNNING = 2 |
|
static |
dynamic_reconfigure::Server<camera1394stereo::Camera1394StereoConfig> camera1394stereo_driver::Camera1394StereoDriver::srv_ |
|
private |
volatile uint8_t camera1394stereo_driver::Camera1394StereoDriver::state_ |
|
private |
The documentation for this class was generated from the following files: