#include <format7.h>
Definition at line 63 of file format7.h.
bool Format7::active |
( |
void |
| ) |
|
|
inline |
bool Format7::checkCameraInfo |
( |
const sensor_msgs::CameraInfo & |
cinfo | ) |
|
check whether CameraInfo matches current Format7 image size
- Precondition
- active_ is true.
- Parameters
-
cinfo | CameraInfo message to check |
- Returns
- true if camera dimensions match calibration
- Postcondition
- fields filled in (if successful): roi (region of interest) binning_x, binning_y
Definition at line 406 of file format7stereo.cpp.
void Format7::setOperationalParameters |
( |
sensor_msgs::CameraInfo & |
cinfo | ) |
|
set operational data fields in CameraInfo message
- Precondition
- active_ is true.
- Parameters
-
cinfo | CameraInfo message to update |
- Returns
- true if camera dimensions match calibration
- Postcondition
- fields filled in (if successful): roi (region of interest) binning_x, binning_y
Definition at line 440 of file format7stereo.cpp.
bool Format7::start |
( |
dc1394camera_t * |
camera, |
|
|
dc1394video_mode_t |
mode, |
|
|
Config & |
newconfig |
|
) |
| |
Start the 1394 device in Format7 mode
- Parameters
-
| camera | pointer to dc1394camera_t structure. |
| mode | currently selected Format7 video mode. |
[in,out] | newconfig | new configuration parameters. |
- Returns
- true, if successful.
- Postcondition
- active_ true, if successful
- Todo:
- Add some sensible recovery for bad Format7 size.
Definition at line 58 of file format7stereo.cpp.
void Format7::stop |
( |
void |
| ) |
|
void Format7::unpackData |
( |
sensor_msgs::Image & |
image, |
|
|
uint8_t * |
capture_buffer |
|
) |
| |
dc1394color_filter_t Format7::BayerPattern_ |
|
private |
order of pixels in raw image format
Definition at line 104 of file format7.h.
uint32_t Format7::binning_x_ |
|
private |
uint32_t Format7::binning_y_ |
|
private |
dc1394color_coding_t Format7::coding_ |
|
private |
uint32_t Format7::maxHeight_ |
|
private |
uint32_t Format7::maxWidth_ |
|
private |
sensor_msgs::RegionOfInterest Format7::roi_ |
|
private |
currently configured region of interest
Definition at line 97 of file format7.h.
The documentation for this class was generated from the following files: