TriclopsStereoProcessor Class Reference

Stereo processing using PGR Triclops SDK. More...

#include <stereo/triclops.h>

Inheritance diagram for TriclopsStereoProcessor:

List of all members.


Public Member Functions

 TriclopsStereoProcessor (unsigned int width, unsigned int height, const char *context_file)
 Constructor.
 TriclopsStereoProcessor (Camera *camera)
 Constructor.
virtual ~TriclopsStereoProcessor ()
 Destructor.
virtual unsigned int output_image_width ()
 Get width of ouput images.
virtual unsigned int output_image_height ()
 Get height of ouput images.
virtual bool subpixel_interpolation ()
 Check state of subpixel interpolation.
virtual bool edge_correlation ()
 Check state of edge correlation.
virtual bool lowpass ()
 Check state of lowpass filtering.
virtual int disparity_range_min ()
 Get disparity range min value.
virtual int disparity_range_max ()
 Get disparity range max value.
virtual unsigned int edge_masksize ()
 Get edge mask size.
virtual unsigned int stereo_masksize ()
 Get stereo mask size.
virtual bool surface_validation ()
 Check state of surface validation.
virtual bool texture_validation ()
 Check state of texture validation.
virtual unsigned char disparity_mapping_min ()
 Get disparity mapping min value.
virtual unsigned char disparity_mapping_max ()
 Get disparity mapping max value.
virtual bool disparity_mapping ()
 Check state of disparity mapping.
virtual void set_output_image_size (unsigned int width, unsigned int height)
 Set the resolution of the output images.
virtual void set_subpixel_interpolation (bool enabled)
 Enable or disable subpixel interpolation.
virtual void set_edge_correlation (bool enabled)
 Enable or disable edge correlation.
virtual void set_lowpass (bool enabled)
 Enable or disable lowpass filtering before rectification.
virtual void set_disparity_range (int min, int max)
 Set disparity range.
virtual void set_edge_masksize (unsigned int mask_size)
 Set edge mask.
virtual void set_stereo_masksize (unsigned int mask_size)
 Set stereo mask.
virtual void set_surface_validation (bool enabled)
 Enable or disable surface validation.
virtual void set_texture_validation (bool enabled)
 Enable or disable texture validation.
virtual void set_disparity_mapping_range (unsigned char min, unsigned char max)
 Set disparity mapping range.
virtual void set_disparity_mapping (bool enabled)
 Enable or disable disparity mapping.
virtual bool get_xyz (unsigned int px, unsigned int py, float *x, float *y, float *z)
 Get camera-relative coordinates of a point.
virtual bool get_world_xyz (unsigned int px, unsigned int py, float *x, float *y, float *z)
 Get transformed coordinates of a point.
virtual void set_raw_buffer (unsigned char *raw16_buffer)
 Set raw buffer.
virtual void preprocess_stereo ()
 Do any pre-processing needed.
virtual void calculate_disparity (ROI *roi=0)
 Caculate disparity images.
virtual void calculate_yuv (bool both=false)
 Caculate yuv images.
virtual unsigned char * disparity_buffer ()
 Get the disparity image buffer.
virtual size_t disparity_buffer_size () const
 Get disparity buffer size.
virtual unsigned char * yuv_buffer ()
 Get YUV-formatted buffer of reference camera.
virtual unsigned char * auxiliary_yuv_buffer ()
 Get YUV-formatted buffer of auxiliary camera.
void generate_rectification_lut (const char *lut_file)
 Generate rectification LUT.
bool verify_rectification_lut (const char *lut_file)
 Verify rectification LUT.
virtual void getall_world_xyz (float ***buffer, int hoff, int voff, int width, int height, float *settings)
 Calculates all three cartesian coordinates of the entire disparity map The values transformed are given by the window (specified by hoff, voff, width and height).

Detailed Description

Stereo processing using PGR Triclops SDK.

This class uses the Triclops SDK provided by Point Grey Research along with the Bumblebee2 cameras.

Author:
Tim Niemueller

Definition at line 35 of file triclops.h.


Constructor & Destructor Documentation

TriclopsStereoProcessor::TriclopsStereoProcessor ( unsigned int  width,
unsigned int  height,
const char *  context_file 
)

Constructor.

With this ctor you can make the triclops wrapper to work on saved images given the expected image size (of a single image) and the path to the Triclops context from the used camera.

Parameters:
width image width in pixels
height image height in pixels
context_file Triclops context file

Definition at line 119 of file triclops.cpp.

TriclopsStereoProcessor::TriclopsStereoProcessor ( Camera camera  ) 

Constructor.

This constructor initializes this triclops wrapper to work on a real camera.

Parameters:
camera Must be of type Bumblebee2Camera

Definition at line 76 of file triclops.cpp.

References Bumblebee2Camera::buffer(), Bumblebee2Camera::is_bumblebee2(), FirewireCamera::pixel_height(), FirewireCamera::pixel_width(), Bumblebee2Camera::RGB_IMAGE, and Bumblebee2Camera::set_image_number().

TriclopsStereoProcessor::~TriclopsStereoProcessor (  )  [virtual]

Destructor.

Definition at line 231 of file triclops.cpp.


Member Function Documentation

unsigned char * TriclopsStereoProcessor::auxiliary_yuv_buffer (  )  [virtual]

Get YUV-formatted buffer of auxiliary camera.

This will return the YUV buffer of the auxiliary image. This is only available after calling calculate_yuv().

Returns:
YUV buffer of the auxiliary image

Implements StereoProcessor.

Definition at line 688 of file triclops.cpp.

void TriclopsStereoProcessor::calculate_disparity ( ROI roi = 0  )  [virtual]

Caculate disparity images.

Depending on the data the specific stereo processor needs the disparity image is calculated. If a region of interest (ROI) is supplied then only this region is processed.

Parameters:
roi region of interest to process

Implements StereoProcessor.

Definition at line 578 of file triclops.cpp.

References ROI::height, ROI::start, ROI::width, fawkes::point_t::x, and fawkes::point_t::y.

void TriclopsStereoProcessor::calculate_yuv ( bool  both = false  )  [virtual]

Caculate yuv images.

This will calculate YUV images of the cameras. By default only the reference image is converted to YUV, as this is sufficient in most cases. If you need both images specify so as argument. A call to this method is valid only after calling calculate_disparity() as this may rely on data produced there.

Parameters:
both if true, both YUV images are calculated for the left and right camera, if false only the YUV image of the reference camera is calculated (dependant on camera)

Implements StereoProcessor.

Definition at line 567 of file triclops.cpp.

unsigned char * TriclopsStereoProcessor::disparity_buffer (  )  [virtual]

Get the disparity image buffer.

Access method to the disparity image buffer.

Returns:
pointer to the internal disparity image buffer

Implements StereoProcessor.

Definition at line 659 of file triclops.cpp.

size_t TriclopsStereoProcessor::disparity_buffer_size (  )  const [virtual]

Get disparity buffer size.

Returns:
size in bytes of the disparity image buffer

Implements StereoProcessor.

Definition at line 670 of file triclops.cpp.

bool TriclopsStereoProcessor::disparity_mapping (  )  [virtual]

Check state of disparity mapping.

Returns:
true if enabled, false otherwise

Definition at line 544 of file triclops.cpp.

unsigned char TriclopsStereoProcessor::disparity_mapping_max (  )  [virtual]

Get disparity mapping max value.

Returns:
max value for disparity mapping

Definition at line 532 of file triclops.cpp.

unsigned char TriclopsStereoProcessor::disparity_mapping_min (  )  [virtual]

Get disparity mapping min value.

Returns:
min value for disparity mapping

Definition at line 520 of file triclops.cpp.

int TriclopsStereoProcessor::disparity_range_max (  )  [virtual]

Get disparity range max value.

Returns:
disparity range max value

Definition at line 460 of file triclops.cpp.

int TriclopsStereoProcessor::disparity_range_min (  )  [virtual]

Get disparity range min value.

Returns:
disparity range min value

Definition at line 448 of file triclops.cpp.

bool TriclopsStereoProcessor::edge_correlation (  )  [virtual]

Check state of edge correlation.

Returns:
true if enabled, false otherwise

Definition at line 424 of file triclops.cpp.

unsigned int TriclopsStereoProcessor::edge_masksize (  )  [virtual]

Get edge mask size.

Returns:
size of the edge mask

Definition at line 472 of file triclops.cpp.

void TriclopsStereoProcessor::generate_rectification_lut ( const char *  lut_file  ) 

Generate rectification LUT.

This will generate a lookup table that can be used for fast rectification of an image. The lut will be of the dimensions of the currently specified image (either given to the offline context file constructor or as defined by the supplied BB2 camera). The file will use RectificationFile to write two RectificationLookupTable entities, one for each image.

Parameters:
lut_file name of the file to write to. The file will be created if it does not exist and truncated otherwise. The directory where the file has to be stored has to exist.

Definition at line 854 of file triclops.cpp.

References RectificationInfoFile::add_rectinfo_block(), FirewireCamera::guid(), FirewireCamera::model(), RectificationLutInfoBlock::set_mapping(), and FireVisionDataFile::write().

bool TriclopsStereoProcessor::get_world_xyz ( unsigned int  px,
unsigned int  py,
float *  x,
float *  y,
float *  z 
) [virtual]

Get transformed coordinates of a point.

Use this method to get the coordinates in the transformed coordinate system of a given point in the image. It may not be possible to provide such a coordinate if no valid disparity information could be calculated for the given point.

Parameters:
px x coordinate in image
py y coordinate in image
x contains the x coordinate in the camera-relative coordinate system upon successful return
y contains the y coordinate in the camera-relative coordinate system upon successful return
z contains the z coordinate in the camera-relative coordinate system upon successful return
Returns:
true, if valid information could be retrieved. In that case (x, y, z) is filled with the coordinates, false otherwise (x, y, and z are not modified).

Implements StereoProcessor.

Definition at line 794 of file triclops.cpp.

References fawkes::deg2rad(), and get_xyz().

bool TriclopsStereoProcessor::get_xyz ( unsigned int  px,
unsigned int  py,
float *  x,
float *  y,
float *  z 
) [virtual]

Get camera-relative coordinates of a point.

Use this method to get the coordinates in the camera coordinate system of a given point in the image. It may not be possible to provide such a coordinate if no valid disparity information could be calculated for the given point.

Parameters:
px x coordinate in image
py y coordinate in image
x contains the x coordinate in the camera-relative coordinate system upon successful return
y contains the y coordinate in the camera-relative coordinate system upon successful return
z contains the z coordinate in the camera-relative coordinate system upon successful return
Returns:
true, if valid information could be retrieved. In that case (x, y, z) is filled with the coordinates, false otherwise (x, y, and z are not modified).

Implements StereoProcessor.

Definition at line 758 of file triclops.cpp.

Referenced by get_world_xyz().

void TriclopsStereoProcessor::getall_world_xyz ( float ***  buffer,
int  hoff,
int  voff,
int  width,
int  height,
float *  settings 
) [virtual]

Calculates all three cartesian coordinates of the entire disparity map The values transformed are given by the window (specified by hoff, voff, width and height).

settings contains all further information needed (in that order): the angle of the camera, the position of the camera relativ to the robot: x, y, z and the maximum distance of points allowed. Points filtered out by distance are marked as NaN in all three coordinates. Unknown Regions are marked the same way with INFINITY.

Parameters:
buffer buffer for the coordinates, 1st index 0: x; 1: y; 2:z, 2nd index denotes the lines, 3rd index denotes the columns
hoff horizontal offset of the window
voff vertical offset of the window
width width of the window
height height of the window
settings a vector of settings in floating point format (angle,position of camera x, y, z, maximum distance of points)

Definition at line 1007 of file triclops.cpp.

References fawkes::deg2rad().

bool TriclopsStereoProcessor::lowpass (  )  [virtual]

Check state of lowpass filtering.

Returns:
true if enabled, false otherwise

Definition at line 436 of file triclops.cpp.

unsigned int TriclopsStereoProcessor::output_image_height (  )  [virtual]

Get height of ouput images.

Returns:
height of output images

Definition at line 414 of file triclops.cpp.

unsigned int TriclopsStereoProcessor::output_image_width (  )  [virtual]

Get width of ouput images.

Returns:
width of output images

Definition at line 404 of file triclops.cpp.

void TriclopsStereoProcessor::preprocess_stereo (  )  [virtual]

Do any pre-processing needed.

Do all the preprocessing needed to calculate the disparity or the YUV images. This has been split out to be able to do only one thing.

Implements StereoProcessor.

Definition at line 553 of file triclops.cpp.

References Bumblebee2Camera::decode_bayer(), and Bumblebee2Camera::deinterlace_stereo().

void TriclopsStereoProcessor::set_disparity_mapping ( bool  enabled  )  [virtual]

Enable or disable disparity mapping.

Parameters:
enabled true to enable, false to disable

Definition at line 383 of file triclops.cpp.

void TriclopsStereoProcessor::set_disparity_mapping_range ( unsigned char  min,
unsigned char  max 
) [virtual]

Set disparity mapping range.

Parameters:
min minimum disparity
max maximum disparity

Definition at line 373 of file triclops.cpp.

void TriclopsStereoProcessor::set_disparity_range ( int  min,
int  max 
) [virtual]

Set disparity range.

Parameters:
min minimum disparity
max maximum disparity

Definition at line 319 of file triclops.cpp.

void TriclopsStereoProcessor::set_edge_correlation ( bool  enabled  )  [virtual]

Enable or disable edge correlation.

Parameters:
enabled true to enable, false to disable

Definition at line 298 of file triclops.cpp.

void TriclopsStereoProcessor::set_edge_masksize ( unsigned int  mask_size  )  [virtual]

Set edge mask.

Size of the kernel used for edge detection. This value must be in the range [3..13].

Parameters:
mask_size mask size

Definition at line 331 of file triclops.cpp.

void TriclopsStereoProcessor::set_lowpass ( bool  enabled  )  [virtual]

Enable or disable lowpass filtering before rectification.

Parameters:
enabled true to enable, false to disable

Definition at line 308 of file triclops.cpp.

void TriclopsStereoProcessor::set_output_image_size ( unsigned int  width,
unsigned int  height 
) [virtual]

Set the resolution of the output images.

Parameters:
width the width of the output images
height the height of the output images

Definition at line 271 of file triclops.cpp.

void TriclopsStereoProcessor::set_raw_buffer ( unsigned char *  raw16_buffer  )  [virtual]

Set raw buffer.

Parameters:
raw16_buffer buffer containing the stereo image encoded as BB2 RAW16

Definition at line 260 of file triclops.cpp.

void TriclopsStereoProcessor::set_stereo_masksize ( unsigned int  mask_size  )  [virtual]

Set stereo mask.

Size of the mask used for stereo correlation.

Parameters:
mask_size mask size

Definition at line 342 of file triclops.cpp.

void TriclopsStereoProcessor::set_subpixel_interpolation ( bool  enabled  )  [virtual]

Enable or disable subpixel interpolation.

Parameters:
enabled true to enable, false to disable

Definition at line 287 of file triclops.cpp.

void TriclopsStereoProcessor::set_surface_validation ( bool  enabled  )  [virtual]

Enable or disable surface validation.

Parameters:
enabled true to enable, false to disable

Definition at line 352 of file triclops.cpp.

void TriclopsStereoProcessor::set_texture_validation ( bool  enabled  )  [virtual]

Enable or disable texture validation.

Parameters:
enabled true to enable, false to disable

Definition at line 362 of file triclops.cpp.

unsigned int TriclopsStereoProcessor::stereo_masksize (  )  [virtual]

Get stereo mask size.

Returns:
size of the stereo mask

Definition at line 484 of file triclops.cpp.

bool TriclopsStereoProcessor::subpixel_interpolation (  )  [virtual]

Check state of subpixel interpolation.

Returns:
true if enabled, false otherwise

Definition at line 392 of file triclops.cpp.

bool TriclopsStereoProcessor::surface_validation (  )  [virtual]

Check state of surface validation.

Returns:
true if enabled, false otherwise

Definition at line 496 of file triclops.cpp.

bool TriclopsStereoProcessor::texture_validation (  )  [virtual]

Check state of texture validation.

Returns:
true if enabled, false otherwise

Definition at line 508 of file triclops.cpp.

bool TriclopsStereoProcessor::verify_rectification_lut ( const char *  lut_file  ) 

Verify rectification LUT.

Parameters:
lut_file Rectification LUT to verify
Returns:
true if the LUT matches the current camera/context file, false otherwise.

Definition at line 908 of file triclops.cpp.

References RectificationInfoBlock::camera(), RectificationInfoFile::guid(), RectificationLutInfoBlock::mapping(), FireVisionDataFile::num_blocks(), RectificationInfoFile::read(), RectificationInfoFile::rectinfo_blocks(), FireVisionDataFileBlock::type(), and Bumblebee2Camera::verify_guid().

unsigned char * TriclopsStereoProcessor::yuv_buffer (  )  [virtual]

Get YUV-formatted buffer of reference camera.

This will return the YUV buffer of the reference image. This is only available after calling calculate_yuv().

Returns:
YUV buffer of the reference image

Implements StereoProcessor.

Definition at line 681 of file triclops.cpp.


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