TI Autonomous Driving Algorithms (TIADALG) Library User Guide
tiadalg_vl_alg_int.h File Reference
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <assert.h>
#include <stdint.h>
#include <stdarg.h>
#include "tiadalg_interface.h"
#include <./../common/tiadalg_alg_int_interface.h>

Go to the source code of this file.

Data Structures

struct  EL_TI_Pose
 
struct  EL_TI_Kalaman_filter
 
struct  EL_TI_Prms
 
struct  EL_TI_Obj
 This structure is the main handle of EL Module. More...
 

Macros

#define KF_MAXIMUM_MEASUREMENT   (3)
 
#define KF_MAXIMUM_STATE   (9)
 

Typedefs

typedef EL_TI_ObjEL_TI_Handle
 

Enumerations

enum  eMemrecs {
  ALG_HANDLE_MEMREC, ALG_HANDLE_INT_MEMREC, ALG_EXT_MEMREC, ALG_L3D_MEMREC,
  ALG_L2D_MEMREC, ALG_L1D_MEMREC, ALG_TRACK_MEMREC, ALG_TRACK_INT_MEMREC,
  NUM_MEMRECS, ALG_HANDLE_MEMREC, EL_ALG_BUFDESC_VOXEL_INFO_MEM, EL_ALG_BUFDESC_3D_POINTS_MEM,
  EL_ALG_BUFDESC_POINTS_DESC_MEM, EL_ALG_EXT_PERSIST_MEM, EL_ALG_EXT_SCRATCH_MEM, EL_ALG_L2_SCRATCH_MEM,
  NUM_MEMRECS
}
 
enum  eAlgState { ALG_NOT_ACTIVE, ALG_ACTIVE, ALG_NOT_ACTIVE, ALG_ACTIVE }
 

Functions

int32_t EL_TI_numAlloc (void)
 
int32_t EL_TI_alloc (const IALG_Params *params, struct IALG_Fxns **parentFxns, IALG_MemRec *memRec)
 
int32_t EL_TI_init (IALG_Handle handle, const IALG_MemRec *memRec, IALG_Handle parent, const IALG_Params *params)
 
void EL_TI_activate (IALG_Handle handle)
 
void EL_TI_deactivate (IALG_Handle handle)
 
int32_t EL_TI_free (IALG_Handle handle, IALG_MemRec *memRec)
 
int32_t EL_TI_control (IVISION_Handle handle, IALG_Cmd cmd, const IALG_Params *inParams, IALG_Params *outParams)
 
int32_t EL_TI_process (IVISION_Handle handle, IVISION_InBufs *inBufs, IVISION_OutBufs *outBufs, IVISION_InArgs *inArgs, IVISION_OutArgs *outArgs)
 
int32_t EL_TI_pose_filtering (float in_rot[3][3], float in_t[3], float out_rot_mat[3][3], float out_rot_angle[3], float out_t[3], int32_t is_first_frame, int32_t solve_pnp_status, EL_TI_Kalaman_filter *kf, EL_TI_Pose *prev_est_pose, EL_TI_Pose *prev_filt_pose, EL_TI_Pose *cur_filt_pose, EL_TI_Pose *iir_filt_pose)
 
void TIADALG_KF_Correct_F32 (EL_TI_Kalaman_filter *KF, const float *Z, float *Residual)
 
void TIADALG_KF_Predict_F32 (EL_TI_Kalaman_filter *KF)
 
void TIADALG_KF_Init (EL_TI_Kalaman_filter *KF, int32_t num_meas, int32_t num_state, float *tansition_matrix)
 
int32_t TIADALG_gaussJordanElimination_cn (float *a, int32_t n, float *b, int32_t aMatPitch, uint8_t *scratch)
 
static void memset_float (float *dst, float val, int32_t num)
 
void getOrientationFromRotationMat (float rotationMat[3][3], float orientation[3])
 

Macro Definition Documentation

◆ KF_MAXIMUM_MEASUREMENT

#define KF_MAXIMUM_MEASUREMENT   (3)

◆ KF_MAXIMUM_STATE

#define KF_MAXIMUM_STATE   (9)

Typedef Documentation

◆ EL_TI_Handle

Enumeration Type Documentation

◆ eMemrecs

enum eMemrecs
Enumerator
ALG_HANDLE_MEMREC 
ALG_HANDLE_INT_MEMREC 
ALG_EXT_MEMREC 
ALG_L3D_MEMREC 
ALG_L2D_MEMREC 
ALG_L1D_MEMREC 
ALG_TRACK_MEMREC 
ALG_TRACK_INT_MEMREC 
NUM_MEMRECS 
ALG_HANDLE_MEMREC 
EL_ALG_BUFDESC_VOXEL_INFO_MEM 
EL_ALG_BUFDESC_3D_POINTS_MEM 
EL_ALG_BUFDESC_POINTS_DESC_MEM 
EL_ALG_EXT_PERSIST_MEM 
EL_ALG_EXT_SCRATCH_MEM 
EL_ALG_L2_SCRATCH_MEM 
NUM_MEMRECS 

◆ eAlgState

enum eAlgState
Enumerator
ALG_NOT_ACTIVE 
ALG_ACTIVE 
ALG_NOT_ACTIVE 
ALG_ACTIVE 

Function Documentation

◆ EL_TI_numAlloc()

int32_t EL_TI_numAlloc ( void  )

◆ EL_TI_alloc()

int32_t EL_TI_alloc ( const IALG_Params *  params,
struct IALG_Fxns **  parentFxns,
IALG_MemRec *  memRec 
)

◆ EL_TI_init()

int32_t EL_TI_init ( IALG_Handle  handle,
const IALG_MemRec *  memRec,
IALG_Handle  parent,
const IALG_Params *  params 
)

◆ EL_TI_activate()

void EL_TI_activate ( IALG_Handle  handle)

◆ EL_TI_deactivate()

void EL_TI_deactivate ( IALG_Handle  handle)

◆ EL_TI_free()

int32_t EL_TI_free ( IALG_Handle  handle,
IALG_MemRec *  memRec 
)

◆ EL_TI_control()

int32_t EL_TI_control ( IVISION_Handle  handle,
IALG_Cmd  cmd,
const IALG_Params *  inParams,
IALG_Params *  outParams 
)

◆ EL_TI_process()

int32_t EL_TI_process ( IVISION_Handle  handle,
IVISION_InBufs *  inBufs,
IVISION_OutBufs *  outBufs,
IVISION_InArgs *  inArgs,
IVISION_OutArgs *  outArgs 
)

◆ EL_TI_pose_filtering()

int32_t EL_TI_pose_filtering ( float  in_rot[3][3],
float  in_t[3],
float  out_rot_mat[3][3],
float  out_rot_angle[3],
float  out_t[3],
int32_t  is_first_frame,
int32_t  solve_pnp_status,
EL_TI_Kalaman_filter kf,
EL_TI_Pose prev_est_pose,
EL_TI_Pose prev_filt_pose,
EL_TI_Pose cur_filt_pose,
EL_TI_Pose iir_filt_pose 
)

◆ TIADALG_KF_Correct_F32()

void TIADALG_KF_Correct_F32 ( EL_TI_Kalaman_filter KF,
const float *  Z,
float *  Residual 
)

◆ TIADALG_KF_Predict_F32()

void TIADALG_KF_Predict_F32 ( EL_TI_Kalaman_filter KF)

◆ TIADALG_KF_Init()

void TIADALG_KF_Init ( EL_TI_Kalaman_filter KF,
int32_t  num_meas,
int32_t  num_state,
float *  tansition_matrix 
)

◆ TIADALG_gaussJordanElimination_cn()

int32_t TIADALG_gaussJordanElimination_cn ( float *  a,
int32_t  n,
float *  b,
int32_t  aMatPitch,
uint8_t *  scratch 
)

◆ memset_float()

static void memset_float ( float *  dst,
float  val,
int32_t  num 
)
inlinestatic

◆ getOrientationFromRotationMat()

void getOrientationFromRotationMat ( float  rotationMat[3][3],
float  orientation[3] 
)

© Copyright 2018 Texas Instruments Incorporated. All rights reserved.
Document generated by doxygen 1.8.6