#include <driver1394.h>
|
static const uint8_t | CLOSED = 0 |
|
static const uint8_t | OPENED = 1 |
|
static const uint8_t | RUNNING = 2 |
|
|
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) |
|
Definition at line 75 of file driver1394.h.
camera1394_driver::Camera1394Driver::~Camera1394Driver |
( |
| ) |
|
void camera1394_driver::Camera1394Driver::closeCamera |
( |
| ) |
|
|
private |
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.
bool camera1394_driver::Camera1394Driver::openCamera |
( |
Config & |
newconfig | ) |
|
|
private |
Open the camera device.
- Parameters
-
newconfig | configuration 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.
void camera1394_driver::Camera1394Driver::poll |
( |
void |
| ) |
|
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 235 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 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
-
newconfig | new Config values |
level | bit-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.
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 394 of file driver1394.cpp.
void camera1394_driver::Camera1394Driver::shutdown |
( |
void |
| ) |
|
bool camera1394_driver::Camera1394Driver::calibration_matches_ |
|
private |
std::string camera1394_driver::Camera1394Driver::camera_name_ |
|
private |
camera calibration information
Definition at line 127 of file driver1394.h.
const uint8_t camera1394_driver::Camera1394Driver::CLOSED = 0 |
|
static |
camera1394::Camera1394Config camera1394_driver::Camera1394Driver::config_ |
|
private |
dynamic parameter configuration
Definition at line 123 of file driver1394.h.
uint32_t camera1394_driver::Camera1394Driver::consecutive_read_errors_ |
|
private |
ros::Rate camera1394_driver::Camera1394Driver::cycle_ |
|
private |
libdc1394 camera device interface
Definition at line 120 of file driver1394.h.
services for getting/setting camera control and status registers (CSR)
Definition at line 135 of file driver1394.h.
boost::mutex camera1394_driver::Camera1394Driver::mutex_ |
|
private |
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 |
volatile bool camera1394_driver::Camera1394Driver::reconfiguring_ |
|
private |
uint32_t camera1394_driver::Camera1394Driver::retries_ |
|
private |
const uint8_t camera1394_driver::Camera1394Driver::RUNNING = 2 |
|
static |
dynamic_reconfigure::Server<camera1394::Camera1394Config> camera1394_driver::Camera1394Driver::srv_ |
|
private |
volatile uint8_t camera1394_driver::Camera1394Driver::state_ |
|
private |
double camera1394_driver::Camera1394Driver::topic_diagnostics_max_freq_ |
|
private |
double camera1394_driver::Camera1394Driver::topic_diagnostics_min_freq_ |
|
private |
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 Mon Jun 10 2019 12:52:31