ompl::geometric::GAIK Class Reference

Inverse Kinematics with Genetic Algorithms. More...

#include <GAIK.h>

List of all members.

Classes

struct  Individual
struct  IndividualSort

Public Member Functions

 GAIK (const base::SpaceInformationPtr &si)
 Construct an instance of a genetic algorithm for inverse kinematics given the space information to search within.
unsigned int getMaxImproveSteps (void) const
 Get the number of steps to perform when using hill climbing to improve an individual in the population.
unsigned int getPoolMutationSize (void) const
 Get the number of individuals that are mutated at each generation.
unsigned int getPoolRandomSize (void) const
 Get the number of individuals to randomly sample at each generation.
unsigned int getPoolSize (void) const
 Get the number number of individuals in the population.
double getRange (void) const
 Get the range GAIK is using.
bool getValidityCheck (void) const
 Get the state validity flag; if this is false, states are not checked for validity.
void setMaxImproveSteps (unsigned int maxSteps)
 Set the number of steps to perform when using hill climbing to improve an individual in the population.
void setPoolMutationSize (unsigned int size)
 Set the number of individuals to mutate at each generation.
void setPoolRandomSize (unsigned int size)
 Set the number of individuals to randomly sample at each generation.
void setPoolSize (unsigned int size)
 Set the number of individuals in the population.
void setRange (double distance)
 Set the range (distance) to be used when sampling around a state.
void setValidityCheck (bool valid)
 Set the state validity flag; if this is false, states are not checked for validity.
bool solve (double solveTime, const base::GoalRegion &goal, base::State *result, const std::vector< base::State * > &hint=std::vector< base::State * >())
 Find a state that fits the request.
 ~GAIK (void)

Private Member Functions

bool tryToImprove (const base::GoalRegion &goal, base::State *state, double distance)
 Use hill climbing to attempt to get a state closer to the goal.
bool valid (const base::State *state) const
 Return true if the state is to be considered valid. This function always returns true if checking of validity is disabled.

Private Attributes

bool checkValidity_
HCIK hcik_
double maxDistance_
msg::Interface msg_
unsigned int poolMutation_
unsigned int poolRandom_
unsigned int poolSize_
base::SpaceInformationPtr si_

Detailed Description

Inverse Kinematics with Genetic Algorithms.

Short description

GAIK does inverse kinematics, but makes sure the produced goal states are in fact valid.

External documentation

Definition at line 57 of file GAIK.h.


Constructor & Destructor Documentation

ompl::geometric::GAIK::GAIK ( const base::SpaceInformationPtr si  )  [inline]

Construct an instance of a genetic algorithm for inverse kinematics given the space information to search within.

Definition at line 47 of file GAIK.h.

ompl::geometric::GAIK::~GAIK ( void   )  [inline]

Definition at line 54 of file GAIK.h.


Member Function Documentation

unsigned int ompl::geometric::GAIK::getMaxImproveSteps ( void   )  const [inline]

Get the number of steps to perform when using hill climbing to improve an individual in the population.

Definition at line 69 of file GAIK.h.

unsigned int ompl::geometric::GAIK::getPoolMutationSize ( void   )  const [inline]

Get the number of individuals that are mutated at each generation.

Definition at line 106 of file GAIK.h.

unsigned int ompl::geometric::GAIK::getPoolRandomSize ( void   )  const [inline]

Get the number of individuals to randomly sample at each generation.

Definition at line 118 of file GAIK.h.

unsigned int ompl::geometric::GAIK::getPoolSize ( void   )  const [inline]

Get the number number of individuals in the population.

Definition at line 94 of file GAIK.h.

double ompl::geometric::GAIK::getRange ( void   )  const [inline]

Get the range GAIK is using.

Definition at line 130 of file GAIK.h.

bool ompl::geometric::GAIK::getValidityCheck ( void   )  const [inline]

Get the state validity flag; if this is false, states are not checked for validity.

Definition at line 82 of file GAIK.h.

void ompl::geometric::GAIK::setMaxImproveSteps ( unsigned int  maxSteps  )  [inline]

Set the number of steps to perform when using hill climbing to improve an individual in the population.

Definition at line 63 of file GAIK.h.

void ompl::geometric::GAIK::setPoolMutationSize ( unsigned int  size  )  [inline]

Set the number of individuals to mutate at each generation.

Definition at line 100 of file GAIK.h.

void ompl::geometric::GAIK::setPoolRandomSize ( unsigned int  size  )  [inline]

Set the number of individuals to randomly sample at each generation.

Definition at line 112 of file GAIK.h.

void ompl::geometric::GAIK::setPoolSize ( unsigned int  size  )  [inline]

Set the number of individuals in the population.

Definition at line 88 of file GAIK.h.

void ompl::geometric::GAIK::setRange ( double  distance  )  [inline]

Set the range (distance) to be used when sampling around a state.

Definition at line 124 of file GAIK.h.

void ompl::geometric::GAIK::setValidityCheck ( bool  valid  )  [inline]

Set the state validity flag; if this is false, states are not checked for validity.

Definition at line 75 of file GAIK.h.

bool ompl::geometric::GAIK::solve ( double  solveTime,
const base::GoalRegion goal,
base::State result,
const std::vector< base::State * > &  hint = std::vector< base::State * >() 
)

Find a state that fits the request.

bool ompl::geometric::GAIK::tryToImprove ( const base::GoalRegion goal,
base::State state,
double  distance 
) [private]

Use hill climbing to attempt to get a state closer to the goal.

bool ompl::geometric::GAIK::valid ( const base::State state  )  const [inline, private]

Return true if the state is to be considered valid. This function always returns true if checking of validity is disabled.

Definition at line 141 of file GAIK.h.


Member Data Documentation

Definition at line 169 of file GAIK.h.

Definition at line 164 of file GAIK.h.

Definition at line 171 of file GAIK.h.

Definition at line 173 of file GAIK.h.

unsigned int ompl::geometric::GAIK::poolMutation_ [private]

Definition at line 167 of file GAIK.h.

unsigned int ompl::geometric::GAIK::poolRandom_ [private]

Definition at line 168 of file GAIK.h.

unsigned int ompl::geometric::GAIK::poolSize_ [private]

Definition at line 166 of file GAIK.h.

Definition at line 165 of file GAIK.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


ompl
Author(s): Ioan Sucan/isucan@rice.edu, Mark Moll/mmoll@rice.edu, Lydia Kavraki/kavraki@rice.edu
autogenerated on Fri Jan 11 09:34:03 2013