ompl::control::SpaceInformation Class Reference

Space information containing necessary information for planning with controls. setup() needs to be called before use. More...

#include <SpaceInformation.h>

Inheritance diagram for ompl::control::SpaceInformation:
Inheritance graph
[legend]

List of all members.

Public Member Functions

const ControlSpacePtrgetControlSpace (void) const
 Get the control space.
virtual void printSettings (std::ostream &out=std::cout) const
 Print information about the current instance of the state space.
virtual void setup (void)
 Perform additional setup tasks (run once, before use).
 SpaceInformation (const base::StateSpacePtr &stateSpace, const ControlSpacePtr &controlSpace)
 Constructor. Sets the instance of the state and control spaces to plan with.
virtual ~SpaceInformation (void)
Control memory management

ControlallocControl (void) const
 Allocate memory for a control.
ControlcloneControl (const Control *source) const
 Clone a control.
void copyControl (Control *destination, const Control *source) const
 Copy a control to another.
void freeControl (Control *control) const
 Free the memory of a control.
Sampling of controls

ControlSamplerPtr allocControlSampler (void) const
 Allocate a control sampler.
unsigned int getMaxControlDuration (void) const
 Get the maximum number of steps a control is propagated for.
unsigned int getMinControlDuration (void) const
 Get the minimum number of steps a control is propagated for.
double getPropagationStepSize (void) const
 Propagation is performed at integer multiples of a specified step size. This function returns the value of this step size.
void setMinMaxControlDuration (unsigned int minSteps, unsigned int maxSteps)
 Set the minimum and maximum number of steps a control is propagated for.
void setPropagationStepSize (double stepSize)
 When controls are applied to states, they are applied for a time duration that is an integer multiple of the stepSize, within the bounds specified by setMinMaxControlDuration().
Topology-specific control operations (as in the control space)

bool equalControls (const Control *control1, const Control *control2) const
 Check if two controls are the same.
void nullControl (Control *control) const
 Make the control have no effect if it were to be applied to a state for any amount of time.
void printControl (const Control *control, std::ostream &out=std::cout) const
 Print a control to a stream.
Primitives for propagating the model of the system

void propagate (const base::State *state, const Control *control, unsigned int steps, std::vector< base::State * > &result, bool alloc) const
 Propagate the model of the system forward, starting a a given state, with a given control, for a given number of steps.
void propagate (const base::State *state, const Control *control, unsigned int steps, base::State *result) const
 Propagate the model of the system forward, starting a a given state, with a given control, for a given number of steps.
unsigned int propagateWhileValid (const base::State *state, const Control *control, unsigned int steps, std::vector< base::State * > &result, bool alloc) const
 Propagate the model of the system forward, starting at a given state, with a given control, for a given number of steps. Stop if a collision is found and return the number of steps actually performed without collision. If no collision is found, the returned value is equal to the steps argument. If a collision is found after the first step, the return value is 0 and no states are added to result. If alloc is false and result cannot store all the generated states, propagation is stopped prematurely (when result is full). The starting state (state) is not included in result. The return value of the function indicates how many states have been written to result.
unsigned int propagateWhileValid (const base::State *state, const Control *control, unsigned int steps, base::State *result) const
 Propagate the model of the system forward, starting at a given state, with a given control, for a given number of steps. Stop if a collision is found and return the number of steps actually performed without collision. If no collision is found, the returned value is equal to the steps argument. If a collision is found after the first step, the return value is 0 and result = state.

Protected Attributes

ControlSpacePtr controlSpace_
 The control space describing the space of controls applicable to states in the state space.
unsigned int maxSteps_
 The maximum number of steps to apply a control for.
unsigned int minSteps_
 The minimum number of steps to apply a control for.
double stepSize_
 The actual duration of each step.

Detailed Description

Space information containing necessary information for planning with controls. setup() needs to be called before use.

Definition at line 61 of file control/SpaceInformation.h.


Constructor & Destructor Documentation

ompl::control::SpaceInformation::SpaceInformation ( const base::StateSpacePtr stateSpace,
const ControlSpacePtr controlSpace 
) [inline]

Constructor. Sets the instance of the state and control spaces to plan with.

Definition at line 66 of file control/SpaceInformation.h.

virtual ompl::control::SpaceInformation::~SpaceInformation ( void   )  [inline, virtual]

Reimplemented from ompl::base::SpaceInformation.

Definition at line 72 of file control/SpaceInformation.h.


Member Function Documentation

Control* ompl::control::SpaceInformation::allocControl ( void   )  const [inline]

Allocate memory for a control.

Definition at line 86 of file control/SpaceInformation.h.

ControlSamplerPtr ompl::control::SpaceInformation::allocControlSampler ( void   )  const [inline]

Allocate a control sampler.

Definition at line 140 of file control/SpaceInformation.h.

Control* ompl::control::SpaceInformation::cloneControl ( const Control source  )  const [inline]

Clone a control.

Definition at line 104 of file control/SpaceInformation.h.

void ompl::control::SpaceInformation::copyControl ( Control destination,
const Control source 
) const [inline]

Copy a control to another.

Definition at line 98 of file control/SpaceInformation.h.

bool ompl::control::SpaceInformation::equalControls ( const Control control1,
const Control control2 
) const [inline]

Check if two controls are the same.

Definition at line 123 of file control/SpaceInformation.h.

void ompl::control::SpaceInformation::freeControl ( Control control  )  const [inline]

Free the memory of a control.

Definition at line 92 of file control/SpaceInformation.h.

const ControlSpacePtr& ompl::control::SpaceInformation::getControlSpace ( void   )  const [inline]

Get the control space.

Definition at line 77 of file control/SpaceInformation.h.

unsigned int ompl::control::SpaceInformation::getMaxControlDuration ( void   )  const [inline]

Get the maximum number of steps a control is propagated for.

Definition at line 172 of file control/SpaceInformation.h.

unsigned int ompl::control::SpaceInformation::getMinControlDuration ( void   )  const [inline]

Get the minimum number of steps a control is propagated for.

Definition at line 166 of file control/SpaceInformation.h.

double ompl::control::SpaceInformation::getPropagationStepSize ( void   )  const [inline]

Propagation is performed at integer multiples of a specified step size. This function returns the value of this step size.

Definition at line 153 of file control/SpaceInformation.h.

void ompl::control::SpaceInformation::nullControl ( Control control  )  const [inline]

Make the control have no effect if it were to be applied to a state for any amount of time.

Definition at line 129 of file control/SpaceInformation.h.

void ompl::control::SpaceInformation::printControl ( const Control control,
std::ostream &  out = std::cout 
) const [inline]

Print a control to a stream.

Definition at line 117 of file control/SpaceInformation.h.

virtual void ompl::control::SpaceInformation::printSettings ( std::ostream &  out = std::cout  )  const [virtual]

Print information about the current instance of the state space.

Reimplemented from ompl::base::SpaceInformation.

void ompl::control::SpaceInformation::propagate ( const base::State state,
const Control control,
unsigned int  steps,
std::vector< base::State * > &  result,
bool  alloc 
) const

Propagate the model of the system forward, starting a a given state, with a given control, for a given number of steps.

Parameters:
state the state to start at
control the control to apply
steps the number of time steps to apply the control for. Each time step is of length getPropagationStepSize()
result the set of states along the propagated motion
alloc flag indicating whether memory for the states in result should be allocated
Note:
Start state state is not included in result
void ompl::control::SpaceInformation::propagate ( const base::State state,
const Control control,
unsigned int  steps,
base::State result 
) const

Propagate the model of the system forward, starting a a given state, with a given control, for a given number of steps.

Parameters:
state the state to start at
control the control to apply
steps the number of time steps to apply the control for. Each time step is of length getPropagationStepSize()
result the state at the end of the propagation
unsigned int ompl::control::SpaceInformation::propagateWhileValid ( const base::State state,
const Control control,
unsigned int  steps,
std::vector< base::State * > &  result,
bool  alloc 
) const

Propagate the model of the system forward, starting at a given state, with a given control, for a given number of steps. Stop if a collision is found and return the number of steps actually performed without collision. If no collision is found, the returned value is equal to the steps argument. If a collision is found after the first step, the return value is 0 and no states are added to result. If alloc is false and result cannot store all the generated states, propagation is stopped prematurely (when result is full). The starting state (state) is not included in result. The return value of the function indicates how many states have been written to result.

Parameters:
state the state to start at
control the control to apply
steps the maximum number of time steps to apply the control for. Each time step is of length getPropagationStepSize()
result the set of states along the propagated motion (only valid states included)
alloc flag indicating whether memory for the states in result should be allocated
unsigned int ompl::control::SpaceInformation::propagateWhileValid ( const base::State state,
const Control control,
unsigned int  steps,
base::State result 
) const

Propagate the model of the system forward, starting at a given state, with a given control, for a given number of steps. Stop if a collision is found and return the number of steps actually performed without collision. If no collision is found, the returned value is equal to the steps argument. If a collision is found after the first step, the return value is 0 and result = state.

Parameters:
state the state to start at
control the control to apply
steps the maximum number of time steps to apply the control for. Each time step is of length getPropagationStepSize()
result the state at the end of the propagation or the last valid state if a collision is found
void ompl::control::SpaceInformation::setMinMaxControlDuration ( unsigned int  minSteps,
unsigned int  maxSteps 
) [inline]

Set the minimum and maximum number of steps a control is propagated for.

Definition at line 159 of file control/SpaceInformation.h.

void ompl::control::SpaceInformation::setPropagationStepSize ( double  stepSize  )  [inline]

When controls are applied to states, they are applied for a time duration that is an integer multiple of the stepSize, within the bounds specified by setMinMaxControlDuration().

Definition at line 147 of file control/SpaceInformation.h.

virtual void ompl::control::SpaceInformation::setup ( void   )  [virtual]

Perform additional setup tasks (run once, before use).

Reimplemented from ompl::base::SpaceInformation.


Member Data Documentation

The control space describing the space of controls applicable to states in the state space.

Definition at line 232 of file control/SpaceInformation.h.

The maximum number of steps to apply a control for.

Definition at line 238 of file control/SpaceInformation.h.

The minimum number of steps to apply a control for.

Definition at line 235 of file control/SpaceInformation.h.

The actual duration of each step.

Definition at line 241 of file control/SpaceInformation.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:02 2013