triclopsstereo.h
Go to the documentation of this file.
00001 /**************************************************************************************************
00002  Software License Agreement (BSD License)
00003 
00004  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
00005  All rights reserved.
00006 
00007  Redistribution and use in source and binary forms, with or without modification, are permitted
00008  provided that the following conditions are met:
00009 
00010   *Redistributions of source code must retain the above copyright notice, this list of
00011    conditions and the following disclaimer.
00012   *Redistributions in binary form must reproduce the above copyright notice, this list of
00013    conditions and the following disclaimer in the documentation and/or other materials provided
00014    with the distribution.
00015   *Neither the name of the University of Aveiro nor the names of its contributors may be used to
00016    endorse or promote products derived from this software without specific prior written permission.
00017  
00018  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
00019  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
00020  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
00021  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00022  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00023  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
00024  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
00025  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 ***************************************************************************************************/
00032 //=============================================================================
00033 // Copyright © 2004 Point Grey Research, Inc. All Rights Reserved.
00034 // 
00035 // This software is the confidential and proprietary information of Point
00036 // Grey Research, Inc. ("Confidential Information").  You shall not
00037 // disclose such Confidential Information and shall use it only in
00038 // accordance with the terms of the license agreement you entered into
00039 // with Point Grey Research, Inc. (PGR).
00040 // 
00041 // PGR MAKES NO REPRESENTATIONS OR WARRANTIES ABOUT THE SUITABILITY OF THE
00042 // SOFTWARE, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE
00043 // IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
00044 // PURPOSE, OR NON-INFRINGEMENT. PGR SHALL NOT BE LIABLE FOR ANY DAMAGES
00045 // SUFFERED BY LICENSEE AS A RESULT OF USING, MODIFYING OR DISTRIBUTING
00046 // THIS SOFTWARE OR ITS DERIVATIVES.
00047 //
00048 //=============================================================================
00049 //=============================================================================
00050 // $Id: triclopsstereo.h,v 2.3 2010/06/21 18:46:08 arturp Exp $
00051 //=============================================================================
00052 #ifndef TRICLOPSSTEREO_H
00053 #define TRICLOPSSTEREO_H
00054 
00055 //=============================================================================
00056 //
00057 // This file defines the API for Stereo related functions in the 
00058 // Triclops Stereo Vision SDK.
00059 //
00060 //=============================================================================
00061 
00062 
00063 //=============================================================================
00064 // Defines
00065 //=============================================================================
00066 
00067 //=============================================================================
00068 // System Includes  
00069 //=============================================================================
00070 
00071 #include <triclops.h>
00072 
00073 #ifdef __cplusplus
00074 extern "C"
00075 {
00076 #endif
00077    
00078 //=============================================================================
00079 // Macros  
00080 //=============================================================================
00081 
00082 //=============================================================================
00083 // Enumerations  
00084 //=============================================================================
00085 
00086 //=============================================================================
00087 // Types  
00088 //=============================================================================
00089 //
00090 // Group = Types
00091 
00092 //
00093 // Name: TriclopsStereoQuality
00094 //
00095 // Description:
00096 //    This enumerated type identifies stereo algorithm used
00097 // to compute the disparity images. In general, the higher quality of algorithm
00098 // chosen, the more processing time required to compute the result.
00099 //
00100 typedef enum TriclopsStereoQuality
00101 {
00102    TriStereoQlty_STANDARD,
00103    TriStereoQlty_ENHANCED      
00104 } TriclopsStereoQuality;
00105 
00106 //
00107 // Name: TriclopsROI
00108 // 
00109 // Description:
00110 //  This structure describes a Region Of Interest for selective processing 
00111 //  of the input images.  
00112 //
00113 typedef struct TriclopsROI
00114 {
00115    // The row value for the upper-left corner of the region of interest. 
00116    int   row;   
00117    // The column value for the upper-left corner of the region of interest. 
00118    int   col;
00119    // The height of the region of interest. 
00120    int   nrows;
00121    // The width of the region of interest. 
00122    int   ncols;
00123 
00124 } TriclopsROI;
00125 
00126 //=============================================================================
00127 // Function Prototypes  
00128 //=============================================================================
00129 
00130 //=============================================================================
00131 // Stereo
00132 //=============================================================================
00133 //
00134 // Group = Stereo
00135 
00136 //
00137 // Name: triclopsGetROIs
00138 //
00139 // Synopsis:
00140 //  Retrieves a handle to an array of Regions Of Interest.
00141 //
00142 // Input:
00143 //  context - The context.
00144 //
00145 // Output:
00146 //  rois    - A pointer to a 1D array of ROI structures.
00147 //  maxROIs - The maximum number of ROIs allowed.       
00148 //
00149 // Returns:
00150 //  TriclopsErrorOk             - The operation succeeded.
00151 //  InvalidContext - The input context was invalid.     
00152 //
00153 // Description:
00154 //  This function returns a pointer to an array of region of interest (ROI) 
00155 //  structures.  The user may set requested region of interest boundaries in 
00156 //  this array.  The Regions Of Interest that will be valid must begin with 
00157 //  the 0th element in the array and continue in a contiguous manner.  After 
00158 //  having set the Regions Of Interest, the user must call 
00159 //  triclopsSetNumberOfROIs() to indicate to the stereo kernel how many ROIs 
00160 //  he/she wishes processed.  Currently, ROIs are only applied during the 
00161 //  stereo processing, not during preprocessing.
00162 //
00163 // See Also:
00164 //  triclopsSetNumberOfROIs(), triclopsStereo(), TriclopsROI
00165 //
00166 TriclopsError
00167 triclopsGetROIs( TriclopsContext  context,
00168                  TriclopsROI**    rois,
00169                  int*             maxROIs );
00170 
00171 //
00172 // Name: triclopsSetNumberOfROIs
00173 //
00174 // Synopsis:
00175 //  Sets the number of Regions Of Interest the user currently wants active.
00176 //
00177 // Input:
00178 //  context - The context.
00179 //  nrois   - Number of ROIs.
00180 //
00181 // Returns:
00182 //  TriclopsErrorOk             - The operation succeeded.
00183 //  InvalidContext - The input context was invalid.
00184 //  InvalidSetting - Too many ROIs.     
00185 //
00186 // Description:
00187 //  This function indicates to the stereo kernel how many ROIs in the ROI array 
00188 //  will be processed.  Before calling this function, the user must first call 
00189 //  triclopsGetROIs() and set up the ROIs he/she intends to use.  If nrois is
00190 //  set to 0, the entire image will be processed.  This is the default setting.
00191 //
00192 // See Also:
00193 //  triclopsGetROIs()
00194 //
00195 TriclopsError
00196 triclopsSetNumberOfROIs( TriclopsContext context, 
00197                          int             nrois );
00198 
00199 
00200 //
00201 // Name: triclopsGetMaxThreadCount
00202 //
00203 // Synopsis:
00204 //  Retrieves the maximum number of threads used in multi-threaded calls
00205 //
00206 // Input:
00207 //  context - The context.
00208 //
00209 // Output:
00210 //  rois    - A pointer to a 1D array of ROI structures.
00211 //  maxROIs - The maximum number of ROIs allowed.       
00212 //
00213 // Returns:
00214 //  TriclopsErrorOk - The operation succeeded.
00215 //  InvalidContext - The input context was invalid.     
00216 //
00217 // Description:
00218 //  This function returns the maximum number of threads allowed in multuthreaded
00219 //  operations.
00220 //
00221 // See Also:
00222 //  triclopsSetMaxThreadCount(), triclopsStereo()
00223 //
00224 TriclopsError
00225 triclopsGetMaxThreadCount( TriclopsContext  context, int* maxThreadCount );
00226 
00227 //
00228 // Name: triclopsSetMaxThreadCount
00229 //
00230 // Synopsis:
00231 //  Sets the maximum number of threads to use in multi-threaded operations
00232 //
00233 // Input:
00234 //  context - The context.
00235 //  nrois   - maximum number of threads (minimum 1)
00236 //
00237 // Returns:
00238 //  TriclopsErrorOk - The operation succeeded.
00239 //  InvalidContext - The input context was invalid.
00240 //  InvalidSetting - Invalid number passed in (less then 1).    
00241 //  InvalidRequest - the kernel is busy executing in the background
00242 //
00243 // Description:
00244 //  This function indicates to the stereo kernel at what number to cap the number
00245 //  of threads used in multi-threaded operations. If not set, the kernel will use
00246 //  a default number based on the architecture of the machine and the expected 
00247 //  sppedup.
00248 //
00249 // See Also:
00250 //  triclopsGetMaxThreadCount(), triclopsStereo()
00251 //
00252 TriclopsError
00253 triclopsSetMaxThreadCount( TriclopsContext context, int maxThreadCount );
00254 
00255 //
00256 // Name: triclopsSetEdgeCorrelation
00257 //
00258 // Synopsis:
00259 //  Turns edge based correlation on or off.
00260 //
00261 // Input:
00262 //  context - The context.
00263 //  on      - A Boolean value indicating whether correlation should be turned on
00264 //            or off.   
00265 //
00266 // Returns:
00267 //  TriclopsErrorOk             - The operation succeeded.
00268 //  InvalidContext - The input context was invalid.     
00269 //
00270 // Description:
00271 //  Edge based correlation is required for texture and uniqueness 
00272 //  validation to be used.
00273 //
00274 // See Also:
00275 //  triclopsGetEdgeCorrelation(), triclopsSetTextureValidation(), 
00276 //  triclopsSetUniquenessValidation()
00277 //
00278 TriclopsError
00279 triclopsSetEdgeCorrelation( TriclopsContext   context,
00280                             TriclopsBool      on );
00281 
00282 //
00283 // Name: triclopsGetEdgeCorrelation
00284 //
00285 // Synopsis:
00286 //  Retrieves the state of the edge based correlation flag.
00287 // 
00288 // Input:
00289 //  context - The context.
00290 //  
00291 // Output:      
00292 //  on - A pointer to a Boolean that will contain the current setting.
00293 //
00294 // Returns:
00295 //  TriclopsErrorOk             - The operation succeeded.
00296 //  InvalidContext - The input context was invalid.     
00297 //
00298 // See Also:
00299 //  triclopsSetEdgeCorrelation()
00300 //
00301 TriclopsError
00302 triclopsGetEdgeCorrelation( const TriclopsContext       context,
00303                             TriclopsBool*               on );
00304 
00305 //
00306 // Name: triclopsSetEdgeMask
00307 //
00308 // Synopsis:
00309 //  Sets the edge detection mask size.
00310 // 
00311 // Input:
00312 //  context  - The context.
00313 //  masksize - The new mask size, which is valid between 3 and 11.
00314 //
00315 // Returns:
00316 //  TriclopsErrorOk             - The operation succeeded.
00317 //  InvalidContext - The input context was invalid.     
00318 //
00319 // See Also:
00320 //  triclopsGetEdgeMask()
00321 // 
00322 TriclopsError
00323 triclopsSetEdgeMask( TriclopsContext      context,
00324                      int                  masksize );
00325 
00326 //
00327 // Name: triclopsGetEdgeMask
00328 //
00329 // Synopsis:
00330 //  Retrieves the edge detection mask size.
00331 //
00332 // Input:
00333 //  context - The context.
00334 //
00335 // Output:
00336 //  masksize - A pointer to an integer that will contain the current mask size.
00337 //
00338 // Returns:
00339 //  TriclopsErrorOk             - The operation succeeded.
00340 //  InvalidContext - The input context was invalid.
00341 //
00342 // See Also:
00343 //  triclopsSetEdgeMask()
00344 //
00345 TriclopsError
00346 triclopsGetEdgeMask( const TriclopsContext      context,
00347                      int*                       masksize );
00348 
00349 //
00350 // Name: triclopsSetDoStereo
00351 //
00352 // Synopsis:
00353 //  Turns stereo processing on or off.
00354 //
00355 // Input:
00356 //  context - The context.
00357 //  on      - A Boolean indicating whether stereo processing should be turned on
00358 //            or off.   
00359 //
00360 // Returns:
00361 //  TriclopsErrorOk             - The operation succeeded.
00362 //  InvalidContext - The input context was invalid.     
00363 //
00364 // See Also:
00365 //  triclopsGetDoStereo(), triclopsSetStereoQuality(), triclopsGetStereoQuality()
00366 //
00367 TriclopsError
00368 triclopsSetDoStereo( TriclopsContext    context,
00369                      TriclopsBool       on );
00370 
00371 //
00372 // Name: triclopsGetDoStereo
00373 //
00374 // Synopsis:
00375 //  Retrieves the state of the stereo processing.
00376 //
00377 // Input:
00378 //  context - The context.
00379 //
00380 // Output:
00381 //  on - A pointer to a Boolean that will store the current setting.
00382 //
00383 // Returns:
00384 //  TriclopsErrorOk             - The operation succeeded.
00385 //  InvalidContext - The input context was invalid.
00386 //
00387 // See Also:
00388 //  triclopsSetDoStereo(), triclopsSetStereoQuality(), triclopsGetStereoQuality()
00389 //
00390 TriclopsError
00391 triclopsGetDoStereo( const TriclopsContext      context,
00392                      TriclopsBool*              on );
00393 
00394 //
00395 // Name: triclopsSetStereoQuality
00396 //
00397 // Description:
00398 //    Sets the quality of the stereo algorithm to use during stereo processing.
00399 // Higher-quality algorithms will generally require more processing time, but
00400 // give more accurate and/or more complete results. Currently available are 
00401 // TriStereoQlty_STANDARD, our classic stereo algorithm, and 
00402 // TriStereoQlty_ENHANCED, which provides a more reliable sub-pixel disparity 
00403 // estimate.
00404 //
00405 // Input:
00406 //    context     - The current TriclopsContext.
00407 //    quality     - The desired quality of the stereo algorithm to use
00408 //
00409 // Returns:
00410 //    TriclopsErrorOk               - The operation succeeded.
00411 //    TriclopsErrorInvalidContext   - If the context is invalid.
00412 //
00413 // See Also:
00414 //    triclopsGetStereoAlgQuality()
00415 //
00416 TriclopsError
00417 triclopsSetStereoQuality(TriclopsContext context, TriclopsStereoQuality quality);
00418 
00419 //
00420 // Name: triclopsGetStereoQuality
00421 //
00422 // Description:
00423 //    Gets the quality of the stereo algorithm currently in use for stereo 
00424 // processing.
00425 //
00426 // Input:
00427 //    context     - The current TriclopsContext.
00428 //    quality     - The quality of the stereo algorithm currently in use.
00429 //
00430 // Returns:
00431 //    TriclopsErrorOk               - The operation succeeded.
00432 //    TriclopsErrorInvalidContext   - If the context is invalid.
00433 //
00434 // See Also:
00435 //    triclopsSetStereoAlgQuality()
00436 //
00437 TriclopsError
00438 triclopsGetStereoQuality(TriclopsContext context, TriclopsStereoQuality* quality);
00439 
00440 //
00441 // Name: triclopsSetSubpixelInterpolation
00442 //
00443 // Synopsis:
00444 //  Turns subpixel interpolation stereo improvements on or off.
00445 //
00446 // Input:
00447 //  context - The context.
00448 //  on      - A Boolean indicating whether it should be on or off.      
00449 //
00450 // Returns:
00451 //  TriclopsErrorOk             - The operation succeeded.
00452 //  InvalidContext - The input context was invalid.     
00453 //
00454 // See Also:
00455 //  triclopsGetSubpixelInterpolation(), triclopsSetStrictSubpixelValidation()
00456 //
00457 TriclopsError
00458 triclopsSetSubpixelInterpolation( TriclopsContext       context,
00459                                   TriclopsBool          on );
00460 
00461 //
00462 // Name: triclopsGetSubpixelInterpolation
00463 //
00464 // Synopsis:
00465 //  Retrieves the state of the subpixel interpolation feature.
00466 //
00467 // Input:
00468 //  context - The context.
00469 //
00470 // Output:
00471 //  on - A pointer to a Boolean that will store the current setting.
00472 //
00473 // Returns:
00474 //  TriclopsErrorOk             - The operation succeeded.
00475 //  InvalidContext - The specified context was invalid. 
00476 //
00477 // See Also
00478 //  triclopsSetSubpixelInterpolation(), triclopsSetStrictSubpixelValidation()
00479 //
00480 TriclopsError
00481 triclopsGetSubpixelInterpolation( const TriclopsContext   context,
00482                                   TriclopsBool*           on );
00483 
00484 //
00485 // Name: triclopsSetDisparity
00486 //
00487 // Synopsis:
00488 //  Sets the disparity range for stereo processing. Currently, the range
00489 // must be such that (maxDisparity-minDisparity<=240) and (maxDisparity<=1024). 
00490 // Note that a side-effect of setting maxDisparity > 240 is that the disparity
00491 // offset is set to maxDisparity-240.
00492 //
00493 // Input:
00494 //  context      - The context.
00495 //  minDisparity - The disparity range minimum.
00496 //  maxDisparity - The disparity range maximum. 
00497 //
00498 // Returns:
00499 //  TriclopsErrorOk             - The operation succeeded.
00500 //  InvalidContext - The input context was invalid.     
00501 //
00502 // See Also:
00503 //  triclopsGetDisparityOffset.
00504 //
00505 TriclopsError
00506 triclopsSetDisparity( TriclopsContext   context, 
00507                       int               minDisparity, 
00508                       int               maxDisparity );
00509 
00510 //
00511 // Name: triclopsGetDisparity
00512 //
00513 // Synopsis:
00514 //  Retrieves the disparity range from the given context.
00515 //
00516 // Input:
00517 //  context - The context
00518 //
00519 // Output:
00520 //  minDisparity - A pointer to an integer that will store the current value.
00521 //  maxDisparity - A pointer to an integer that will store the current value.   
00522 //
00523 // Returns:
00524 //  TriclopsErrorOk             - The operation succeeded.
00525 //  InvalidContext - The input context was invalid.     
00526 //
00527 // See Also:
00528 //  triclopsGetDisparityOffset.
00529 //
00530 TriclopsError
00531 triclopsGetDisparity( const TriclopsContext     context, 
00532                       int*                      minDisparity, 
00533                       int*                      maxDisparity );
00534 
00535 //
00536 // Name: triclopsGetDisparityOffset
00537 //
00538 // Synopsis:
00539 //  Retrieves the disparity offset from the given context. Adding the disparity
00540 //  offset to a valid disparity value from the disparity image gives the 
00541 //  true disparity value. The disparity offset is set automatically when the
00542 //  disparity range is set using triclopsSetDisparity, and is equal to
00543 //  MAX( 0, maxDisparity-240). The disparity offset allows the disparity range, 
00544 //  (which has a maximum extent of 240) to be shifted up away from zero, so 
00545 //  that objects very close to the camera may be imaged.
00546 //
00547 // Input:
00548 //  context - The context
00549 //
00550 // Output:
00551 //  nDisparityOffset - A pointer to an integer that will store the current value.
00552 //
00553 // Returns:
00554 //  TriclopsErrorOk - The operation succeeded.
00555 //  InvalidContext  - The input context was invalid.    
00556 //
00557 TriclopsError
00558 triclopsGetDisparityOffset( const TriclopsContext       context, 
00559                             int*                        nDisparityOffset );
00560 
00561 //
00562 // Name: triclopsSetDisparityMappingOn
00563 //
00564 // Synopsis:
00565 //  Enables or disables disparity mapping.
00566 // 
00567 // Input:
00568 //  context - TriclopsContext for the operation.                
00569 //  on      - A Boolean flag indicating if the mapping should be on or off.             
00570 //
00571 // Returns:
00572 //  TriclopsErrorOk                          - Operation successful.
00573 //  TriclopsErrorInvalidContext - Context is not a valid TriclopsContext. 
00574 //
00575 // Description:
00576 //  This function is used to enable or disable disparity mapping.  See the 
00577 //  comments section on this subject in Chapter 7 in the Triclops manual for 
00578 //  why disparity mapping can cause trouble.
00579 //
00580 //
00581 TriclopsError
00582 triclopsSetDisparityMappingOn( TriclopsContext  context, 
00583                                TriclopsBool     on );
00584 
00585 //
00586 // Name: triclopsGetDisparityMappingOn
00587 //
00588 // Synopsis:
00589 //  Retrieves the current setting.
00590 //
00591 // Input:
00592 //  context - TriclopsContext for the operation.
00593 //
00594 // Output:
00595 //  on - A pointer that will contain the current value of this flag.
00596 //
00597 // Returns:
00598 //  TriclopsErrorOk                          - Operation successful. 
00599 //  TriclopsErrorInvalidContext - Context is not a valid TriclopsContext.
00600 //
00601 // Description:
00602 //  This function is used to extract the current disparity mapping setting.
00603 //
00604 // See Also:
00605 //  triclopsSetDisparityMappingOn.
00606 //
00607 TriclopsError
00608 triclopsGetDisparityMappingOn( TriclopsContext  context, 
00609                                TriclopsBool*    on );
00610 
00611 //
00612 // Name: triclopsSetDisparityMapping
00613 //
00614 // Synopsis:
00615 //  Sets the disparity range for stereo processing.
00616 //
00617 // Input:
00618 //  context      - The context.
00619 //  minDisparity - The disparity range in the output disparity image minimum.
00620 //                 The range is between 0 and 255.
00621 //  maxDisparity - The disparity range in the output disparity image maximum.
00622 //                 The range is between 0 and 255.
00623 //
00624 // Returns:
00625 //  TriclopsErrorOk             - The operation succeeded.
00626 //  InvalidContext - The input context was invalid.     
00627 // 
00628 // Description:
00629 //  This function sets the disparity mapping values.  The disparity mapping 
00630 //  values control what range of pixels values appear in the output disparity 
00631 //  image.  The true disparity ranges between the minimum and maximum values 
00632 //  set with triclopsSetDisparity().  The output image has its pixel values 
00633 //  linearly scaled from minimum => maximum disparity  to minimum => maximum 
00634 //  disparity mapping.  This is primarily used when one wishes to use a screen 
00635 //  display buffer as the disparity image buffer.  Note:  it is advisable to 
00636 //  set the disparity mapping to the exact values of the input disparities if 
00637 //  one is not using the screen buffer display feature.
00638 //
00639 // See Also:
00640 //  triclopsGetDisparityMapping(), triclopsSetDisparity(), triclopsRCD8ToXYZ(), 
00641 //  triclopsRCD16ToXYZ(), triclopsRCDMappedToXYZ()
00642 //
00643 TriclopsError
00644 triclopsSetDisparityMapping( TriclopsContext   context, 
00645                              unsigned char     minDisparity, 
00646                              unsigned char     maxDisparity );
00647 
00648 //
00649 // Name: triclopsGetDisparityMapping
00650 //
00651 // Synopsis:
00652 //  Retrieves the disparity range from the given context.
00653 //
00654 // Input:
00655 //  context - The context.
00656 // 
00657 // Output:      
00658 //  minDisparity - The disparity range in the output disparity image minimum.
00659 //  maxDisparity - The disparity range in the output disparity image maximum.
00660 //
00661 // Returns:
00662 //  TriclopsErrorOk             - The operation succeeded.
00663 //  InvalidContext - The input context was invalid.     
00664 //
00665 // See Also:
00666 //  triclopsSetDisparityMapping(), triclopsSetDisparity()
00667 //
00668 TriclopsError
00669 triclopsGetDisparityMapping( const TriclopsContext      context, 
00670                              unsigned char*             minDisparity, 
00671                              unsigned char*             maxDisparity );
00672 
00673 //
00674 // Name: triclopsSetStereoMask
00675 //
00676 // Synopsis:
00677 //  Set the stereo correlation mask size.
00678 //
00679 // Input:
00680 //  context  - The context.
00681 //  masksize - The new correlation mask size, which is valid between 1 and 15.
00682 //
00683 // Returns:
00684 //  TriclopsErrorOk             - The operation succeeded.
00685 //  InvalidContext - The input context was invalid.     
00686 //  
00687 TriclopsError
00688 triclopsSetStereoMask( TriclopsContext  context,
00689                        int              masksize );
00690 
00691 //
00692 // Name: triclopsSetAnyStereoMask
00693 //
00694 // Synopsis:
00695 //  Allows the user to set stereomask to any size. 
00696 //
00697 // Input:
00698 //  context - TriclopsContext for the operation.                
00699 //  size    - The size for a new stereo correlation mask.                       
00700 //
00701 // Returns:
00702 //  TriclopsErrorOk                          - Operation successful.
00703 //  TriclopsErrorInvalidContext - Context is not a valid TriclopsContext.
00704 //  TriclopsErrorInvalidSetting - A value of less than 1        
00705 //
00706 // Description:
00707 //  This function allows you to set a stereo correlation mask of any size.  
00708 //  There is a danger that an internal counter in the stereo correlation 
00709 //  engine may overflow if mask sizes over 15 are provided.  Thus, the 
00710 //  current limit for triclopsSetStereoMask is 15.  However, in practice, 
00711 //  much larger mask sizes can be used successfully.  If an overflow results, 
00712 //  it may not affect the stereo result, and it will generally only happen for 
00713 //  pathological cases.  Therefore, this function is provided as an 
00714 //  'experimental' function to allow users to set any mask size they wish.
00715 //
00716 // See Also:
00717 //  triclopsSetStereoMask()
00718 //
00719 TriclopsError
00720 triclopsSetAnyStereoMask( TriclopsContext       context,
00721                           int                   size );
00722 
00723 //
00724 // Name: triclopsGetStereoMask
00725 //
00726 // Synopsis: 
00727 //  Retrieves the stereo correlation mask size.
00728 // 
00729 // Input:
00730 //  context - The context.
00731 // 
00732 // Output: 
00733 //  size - A pointer to an integer that will store the current value.
00734 //
00735 // Returns:
00736 //  TriclopsErrorOk             - The operation succeeded.
00737 //  InvalidContext - The input context was invalid.     
00738 //
00739 TriclopsError
00740 triclopsGetStereoMask( const TriclopsContext    context,
00741                        int*                     size );
00742 
00743 //
00744 // Name: triclopsStereo
00745 //
00746 // Synopsis:
00747 //  Does stereo processing, validation, and subpixel interpolation, as 
00748 //  specified by parameters.
00749 //
00750 // Input:
00751 //  context - The context.
00752 //
00753 // Returns:
00754 //  TriclopsErrorOk             - The operation succeeded.
00755 //  BadOptions     - There are some contradictory options set.
00756 //  NotImplemented - The context camera configuration is not supported.
00757 //  InvalidROI     - A negative dimensioned ROI, or ROI with illegal starting 
00758 //                   positions was inputted.  Illegal starting position is a
00759 //                   upper/left corner that is closer to the right/bottom edge
00760 //                   of the image than the stereo mask size.    
00761 //  InvalidRequest - triclopsStereo called before triclopsPreprocess ever called.
00762 //
00763 // Description:
00764 //  This function performs the stereo processing and validation, and generates 
00765 //  the internal image TriImg_DISPARITY.
00766 //
00767 // See Also:
00768 //  triclopsPreprocessing(), triclopsSetDoStereo(), triclopsEdgeCorrelation(), 
00769 //  triclopsSetTextureValidation(), triclopsSetUniquenessValidation(), 
00770 //  triclopsGetROIs(), triclopsSetSubpixelInterpolation()
00771 //
00772 TriclopsError
00773 triclopsStereo( TriclopsContext context );
00774 
00775 #ifdef __cplusplus
00776 }
00777 #endif
00778 
00779 #endif  // #ifndef TRICLOPS_H


xb3
Author(s): Miguel Oliveira, Tiago Talhada
autogenerated on Thu Nov 20 2014 11:36:02