TAtlasRRTBranchConfig Struct Reference

Detailed Description

Parameters describing the operation of the AddBranchToAtlasRRT function.

These parameters are grouped in a struct just to clarify the code.

Definition at line 104 of file atlasrrt.c.

Data Fields

unsigned int addMode
 
boolean revisitCharts
 
boolean checkCollisions
 
boolean onManifold
 
boolean explorationSample
 
double maxLength
 
double(* costF )(Tparameters *, boolean, double *, void *)
 
void * costData
 

Field Documentation

unsigned int TAtlasRRTBranchConfig::addMode

Samples to add during the brach extension: all, none, last.

Definition at line 105 of file atlasrrt.c.

Referenced by AddStepToAtlasRRTstar(), InitBranchConfig(), and New_AddBranchToAtlasRRT().

boolean TAtlasRRTBranchConfig::revisitCharts

TRUE if we the chart can enter previously defined charts (in the same tree). FALSE to reduce the branch crossing effect.

Definition at line 106 of file atlasrrt.c.

Referenced by InitBranchConfig(), and New_NewTemptativeSample().

boolean TAtlasRRTBranchConfig::checkCollisions

TRUE if collision stop the branch extension.

Definition at line 108 of file atlasrrt.c.

Referenced by InitBranchConfig(), and New_NewTemptativeSample().

boolean TAtlasRRTBranchConfig::onManifold

TRUE if the random sample is on the manifold (and not in tangent bundle).

Definition at line 109 of file atlasrrt.c.

Referenced by AddStepToAtlasRRTstar(), AtlasRRT(), AtlasTRRT(), InitBranchConfig(), InitBranchStatus(), New_AddBranchToAtlasRRT(), New_NewTemptativeSample(), and New_PointTowardRandSample().

boolean TAtlasRRTBranchConfig::explorationSample

TRUE if we build an exploration branch: a branch towards the unkonwn. FALSE if the branch tries to connect to another tree.

Definition at line 111 of file atlasrrt.c.

Referenced by AtlasRRT(), AtlasTRRT(), InitBranchConfig(), and New_NewTemptativeSample().

double TAtlasRRTBranchConfig::maxLength

Maximum lenght for the branch.

Definition at line 113 of file atlasrrt.c.

Referenced by AtlasBiRRTstar(), InitBranchConfig(), InitBranchStatus(), ReWireAtlasRRTstar(), SmoothPathInAtlasRRT(), and WireAtlasRRTstar().

double(* TAtlasRRTBranchConfig::costF)(Tparameters *, boolean, double *, void *)

Cost function, if any. Only used for T-RRT.

Definition at line 114 of file atlasrrt.c.

Referenced by AtlasTRRT(), InitBranchConfig(), and New_NewTemptativeSample().

void* TAtlasRRTBranchConfig::costData

Data to sent to the cost function.

Definition at line 115 of file atlasrrt.c.

Referenced by AtlasTRRT(), InitBranchConfig(), and New_NewTemptativeSample().