![]() |
TI Autonomous Driving Algorithms (TIADALG) Library User Guide
|
This file defines ivision interface for Structure From Motion (SFM) Algorithm. This module expects optical flow information along with camera pose to generates sparse 3D points. Input image data is needed for visualization purpose only. More...
#include <ivision.h>
Go to the source code of this file.
Data Structures | |
struct | SFM_TI_CreateParams |
This structure contains all the parameters which controls SFM algorithm at create time. More... | |
struct | SFM_TI_InArgs |
This structure contains all the parameters which are given as an input to OD algorithm at frame level. More... | |
struct | SFM_TI_Stats |
This structure reports statistics of running SFM. More... | |
struct | SFM_TI_OutArgs |
This structure contains all the parameters which are given as output. More... | |
struct | SFM_TI_output |
This structure defines the format of output buffer given out from algorithm. More... | |
#define | SFM_TI_CAMERA_EXTRENSIC_PARAM_SIZE (12) |
#define | SFM_TI_CAMERA_INTRINSIC_PARAM_SIZE (9) |
#define | MAX_NUM_FRAMES_TO_TRACK (6) |
enum | SFM_TI_InBufOrder { SFM_TI_IN_BUFDESC_IN_DOF_BUFFER = 0, SFM_TI_IN_BUFDESC_IN_LUMA_IMG_BUFFER = 1, SFM_TI_IN_BUFDESC_TOTAL } |
User provides most of the information through IVISION buffers during process call. Below enums define the purpose of each input buffers. More... | |
enum | SFM_TI_OutBufOrder { SFM_TI_OUT_BUFDESC_FEATURE_PLANES = 0, SFM_TI_OUT_BUFDESC_LUMA_PTCLD_BUFFER = 1, SFM_TI_OUT_BUFDESC_CHROMA_PTCLD_BUFFER = 2, SFM_TI_OUT_BUFDESC_LUMA_OCPGD_BUFFER = 3, SFM_TI_OUT_BUFDESC_CHROMA_OCPGD_BUFFER = 4, SFM_TI_OUT_BUFDESC_TOTAL } |
Process call provides most of the information through IVISION buffers during process call. Below enums define the purpose of each out buffer. More... | |
enum | SFM_TI_FmatrixCalcType { SFM_TI_FMAT_8POINT_RANSAC = 0, SFM_TI_FMAT_FROM_RT_PARAMS = 1, SFM_TI_FMAT_EXT_PRM_NORM_DEFAULT = SFM_TI_FMAT_FROM_RT_PARAMS } |
Defines the method to calculate/estimate Fundamental Matrix. It is recommended to use SFM_TI_FMAT_FROM_RT_PARAMS to save computation cycle. More... | |
const IVISION_Fxns | SFM_TI_VISION_FXNS |
The unique constant function table for SFM. More... | |
This file defines ivision interface for Structure From Motion (SFM) Algorithm. This module expects optical flow information along with camera pose to generates sparse 3D points. Input image data is needed for visualization purpose only.
#define SFM_TI_CAMERA_EXTRENSIC_PARAM_SIZE (12) |
#define SFM_TI_CAMERA_INTRINSIC_PARAM_SIZE (9) |
#define MAX_NUM_FRAMES_TO_TRACK (6) |
enum SFM_TI_InBufOrder |
User provides most of the information through IVISION buffers during process call. Below enums define the purpose of each input buffers.
SFM_TI_IN_BUFDESC_IN_DOF_BUFFER | Input optical flow gnerated from DOF accelerator |
SFM_TI_IN_BUFDESC_IN_LUMA_IMG_BUFFER | Input image buffer |
Enumerator | |
---|---|
SFM_TI_IN_BUFDESC_IN_DOF_BUFFER | |
SFM_TI_IN_BUFDESC_IN_LUMA_IMG_BUFFER | |
SFM_TI_IN_BUFDESC_TOTAL |
enum SFM_TI_OutBufOrder |
Process call provides most of the information through IVISION buffers during process call. Below enums define the purpose of each out buffer.
SFM_TI_OUT_BUFDESC_FEATURE_PLANES | This buffer is filled up by SFM algorithm with a list of estimated 3D points location and their corresponding image pixel location. Output buffer is treated as continuous array of objects of the structure /c SFM_TI_output. Where each object corresponds to information related one reconstructed 3-D point from one track information /c SFM_TI_trackInfo. Output buffer is not image buffer, it is set of objects of 'SFM_TI_output' placed in linear memory. Since number of output buffer is not known at the time of process call, hence out buf should be allocated assuming maximum possible number of 3D output points. Maximum number of out 3D points can be equal to maxNumTracks*6. Hence user should set outBufs :: bufDesc[SFM_TI_OUT_BUFDESC_FEATURE_PLANES] :: bufPlanes[0] ::width greater than or equal to (maxNumTracks*6). maxNumTracks has to be set at the time of create API call. |
SFM_TI_OUT_BUFDESC_LUMA_PTCLD_BUFFER | Luma output buffer with point cloud visualization |
SFM_TI_OUT_BUFDESC_CHROMA_PTCLD_BUFFER | Chroma output buffer with point cloud visualization |
SFM_TI_OUT_BUFDESC_LUMA_OCPGD_BUFFER | Luma output buffer for occupancy grid visualization |
SFM_TI_OUT_BUFDESC_CHROMA_OCPGD_BUFFER | Chroma output buffer for occupancy grid visualization |
Defines the method to calculate/estimate Fundamental Matrix. It is recommended to use SFM_TI_FMAT_FROM_RT_PARAMS to save computation cycle.
SFM_TI_FMAT_8POINT_RANSAC : Estimate using 8 point algorithm with RANSAC iteration. Not varified in this version.
SFM_TI_FMAT_FROM_RT_PARAMS : Calculate it using available rotation and translation parameters provided through extrinsic parameters SFM_TI_InArgs :: camExtPrm
Enumerator | |
---|---|
SFM_TI_FMAT_8POINT_RANSAC | |
SFM_TI_FMAT_FROM_RT_PARAMS | |
SFM_TI_FMAT_EXT_PRM_NORM_DEFAULT |
const IVISION_Fxns SFM_TI_VISION_FXNS |
The unique constant function table for SFM.
|
© Copyright 2018 Texas Instruments Incorporated. All rights reserved. |
Document generated by doxygen 1.8.6 |