frountier_threshold:0.0# dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
frountierNodeRatio:0.1# 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
k_constant:0.0# value used to normalize expresssion. default: 0.0 set in setup()
PRM:
type:geometric::PRM
max_nearest_neighbors:10# use k nearest neighbors. default: 10
PRMstar:
type:geometric::PRMstar
FMT:
type:geometric::FMT
num_samples:1000# number of states that the planner should sample. default: 1000
radius_multiplier:1.1# multiplier used for the nearest neighbors search radius. default: 1.1
nearest_k:1# use Knearest strategy. default: 1
cache_cc:1# use collision checking cache. default: 1
heuristics:0# activate cost to go heuristics. default: 0
extended_fmt:1# activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1
BFMT:
type:geometric::BFMT
num_samples:1000# number of states that the planner should sample. default: 1000
radius_multiplier:1.0# multiplier used for the nearest neighbors search radius. default: 1.0
nearest_k:1# use the Knearest strategy. default: 1
balanced:0# exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1
optimality:1# termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1
heuristics:1# activates cost to go heuristics. default: 1
cache_cc:1# use the collision checking cache. default: 1
extended_fmt:1# Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1
PDST:
type:geometric::PDST
STRIDE:
type:geometric::STRIDE
range:0.0# Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias:0.05# When close to goal select goal, with this probability. default: 0.05
use_projected_distance:0# whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0
degree:16# desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
max_degree:18# max degree of a node in the GNAT. default: 12
min_degree:12# min degree of a node in the GNAT. default: 12
max_pts_per_leaf:6# max points per leaf in the GNAT. default: 6
estimated_dimension:0.0# estimated dimension of the free space. default: 0.0
range:0.0# Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
ProjEST:
type:geometric::ProjEST
range:0.0# Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias:0.05# When close to goal select goal, with this probability. default: 0.05
LazyPRM:
type:geometric::LazyPRM
range:0.0# Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
LazyPRMstar:
type:geometric::LazyPRMstar
SPARS:
type:geometric::SPARS
stretch_factor:3.0# roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
sparse_delta_fraction:0.25# delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
dense_delta_fraction:0.001# delta fraction for interface detection. default: 0.001
max_failures:1000# maximum consecutive failure limit. default: 1000
SPARStwo:
type:geometric::SPARStwo
stretch_factor:3.0# roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
sparse_delta_fraction:0.25# delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
dense_delta_fraction:0.001# delta fraction for interface detection. default: 0.001
max_failures:5000# maximum consecutive failure limit. default: 5000
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robotname="twins">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->