ompl::geometric::HCIK Class Reference

Inverse Kinematics with Hill Climbing. More...

#include <HCIK.h>

List of all members.

Public Member Functions

unsigned int getMaxImproveSteps (void) const
 Get the number of steps to perform.
bool getValidityCheck (void) const
 Get the state validity flag; if this is false, states are not checked for validity.
 HCIK (const base::SpaceInformationPtr &si)
 Constructor.
void setMaxImproveSteps (unsigned int steps)
 Set the number of steps to perform.
void setValidityCheck (bool valid)
 Set the state validity flag; if this is false, states are not checked for validity.
bool tryToImprove (const base::GoalRegion &goal, base::State *state, double nearDistance, double *betterGoalDistance=NULL) const
 Try to improve a state (reduce distance to goal). The updates are performed by sampling near the state, within the specified distance. If improvements were found, the function returns true and the better goal distance is opionally returned.
 ~HCIK (void)

Private Member Functions

bool valid (const base::State *state) const

Private Attributes

bool checkValidity_
unsigned int maxImproveSteps_
base::SpaceInformationPtr si_

Detailed Description

Inverse Kinematics with Hill Climbing.

Short description

HCIK does inverse kinematics with hill climbing, starting from a given state.

External documentation

Definition at line 60 of file HCIK.h.


Constructor & Destructor Documentation

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

Constructor.

Definition at line 65 of file HCIK.h.

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

Definition at line 69 of file HCIK.h.


Member Function Documentation

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

Get the number of steps to perform.

Definition at line 85 of file HCIK.h.

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

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

Definition at line 97 of file HCIK.h.

void ompl::geometric::HCIK::setMaxImproveSteps ( unsigned int  steps  )  [inline]

Set the number of steps to perform.

Definition at line 79 of file HCIK.h.

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

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

Definition at line 91 of file HCIK.h.

bool ompl::geometric::HCIK::tryToImprove ( const base::GoalRegion goal,
base::State state,
double  nearDistance,
double *  betterGoalDistance = NULL 
) const

Try to improve a state (reduce distance to goal). The updates are performed by sampling near the state, within the specified distance. If improvements were found, the function returns true and the better goal distance is opionally returned.

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

Definition at line 104 of file HCIK.h.


Member Data Documentation

Definition at line 111 of file HCIK.h.

Definition at line 110 of file HCIK.h.

Definition at line 109 of file HCIK.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