simOMPL.addGoalState
simOMPL.compute
Description
|
Use OMPL to find a solution for this motion planning task.
It is equivalent to executing:
if simOMPL.solve(task, maxTime) then
simOMPL.simplifyPath(task, maxSimplificationTime)
simOMPL.interpolatePath(task, stateCnt)
path = simOMPL.getPath(task)
end
|
Lua synopsis |
bool solved, float[] states=simOMPL.compute(string taskHandle, float maxTime, float maxSimplificationTime=-1.0, int stateCnt=0)
|
Lua parameters |
maxTime (float): maximum time used for the path searching procedure, in seconds.
maxSimplificationTime (float, default: -1.0): maximum
time used for the path simplification procedure, in seconds. -1 for a
default simplification procedure.
stateCnt (int, default: 0): minimum number of states to be returned. 0 for a default behaviour.
|
Lua return values |
solved (bool): true if a solution has been found.
states (table of float): a table of states, representing the solution, from start to goal. States are specified linearly.
|
Python synopsis |
bool solved, list states=simOMPL.compute(string taskHandle, float maxTime, float maxSimplificationTime=-1.0, int stateCnt=0)
|
See also
|
simOMPL.getGoalDistance simOMPL.getPath simOMPL.getPlannerData simOMPL.hasApproximateSolution simOMPL.hasExactSolution simOMPL.hasSolution simOMPL.interpolatePath simOMPL.setAlgorithm simOMPL.simplifyPath simOMPL.solve simOMPL.drawPath simOMPL.getPath simOMPL.getPathState simOMPL.getPathStateCount simOMPL.getProjectedPathLength simOMPL.getReversedPath simOMPL.projectStates
|
simOMPL.createStateSpace
Description
|
Create a component of the state space for the motion planning problem.
In case of a dubins state space, set additional parameters with simOMPL.setDubinsParams
|
Lua synopsis |
string
stateSpaceHandle=simOMPL.createStateSpace(string name, int type, int
objectHandle, float[] boundsLow, float[] boundsHigh, int
useForProjection, float weight=1.0, int refObjectHandle=-1)
|
Lua parameters |
name (string): a name for this state space
objectHandle (int): the object handle (a joint object
if type is simOMPL.StateSpaceType.joint_position or
.cyclic_joint_position, otherwise a shape)
boundsLow (table of float): lower bounds (if type is pose, specify only the 3 position components)
boundsHigh (table of float): upper bounds (if type is pose, specify only the 3 position components)
useForProjection (int): if true, this object position or joint value will be used for computing a default projection
weight (float, default: 1.0): the weight of this state
space component, used for computing distance between states. Default
value is 1.0
refObjectHandle (int, default: -1): an object handle
relative to which reference frame position/orientations will be
evaluated. Default value is -1, for the absolute reference frame
|
Lua return values |
stateSpaceHandle (string): a handle to the created state space component |
Python synopsis |
string
stateSpaceHandle=simOMPL.createStateSpace(string name, int type, int
objectHandle, list boundsLow, list boundsHigh, int useForProjection,
float weight=1.0, int refObjectHandle=-1)
|
See also
|
simOMPL.destroyStateSpace simOMPL.getStateSpaceDimension simOMPL.setDubinsParams simOMPL.setStateSpace
|
simOMPL.createTask
simOMPL.destroyStateSpace
Description
|
Destroy the spacified state space component.
Note: state space components created during simulation are automatically destroyed when simulation ends.
|
Lua synopsis |
simOMPL.destroyStateSpace(string stateSpaceHandle)
|
Lua parameters |
stateSpaceHandle (string): handle to state space component |
Lua return values |
- |
Python synopsis |
simOMPL.destroyStateSpace(string stateSpaceHandle)
|
See also
|
simOMPL.createStateSpace simOMPL.getStateSpaceDimension simOMPL.setDubinsParams simOMPL.setStateSpace
|
simOMPL.destroyTask
simOMPL.drawPath
Description
|
draw a solution path for the specified motion planning task (as lines) |
Lua synopsis |
int[] dwos=simOMPL.drawPath(string taskHandle, float[] path, float lineSize, float[3] color, int extraAttributes)
|
Lua parameters |
taskHandle (string): the handle of the task
path (table of float): the path, as returned by simOMPL.getPath
lineSize (float): size of the line (in pixels)
color (table of float, size 3): color of the lines
extraAttributes (int): extra attributes to pass to sim.addDrawingObject
|
Lua return values |
dwos (table of int): a table of handles of new drawing objects |
Python synopsis |
list dwos=simOMPL.drawPath(string taskHandle, list path, float lineSize, list color, int extraAttributes)
|
See also
|
simOMPL.compute simOMPL.getPath simOMPL.getPathState simOMPL.getPathStateCount simOMPL.getProjectedPathLength simOMPL.getReversedPath simOMPL.projectStates simOMPL.drawPlannerData simOMPL.removeDrawingObjects
|
simOMPL.drawPlannerData
Description
|
draw planner data (graph) extracted from the specified motion planning task |
Lua synopsis |
int[] dwos=simOMPL.drawPlannerData(string
taskHandle, float pointSize, float lineSize, float[3] color, float[3]
startColor, float[3] goalColor)
|
Lua parameters |
taskHandle (string): handle of the task
pointSize (float): size of nodes (in meters)
lineSize (float): size of lines (in pixels)
color (table of float, size 3): color of nodes and lines
startColor (table of float, size 3): color of start nodes
goalColor (table of float, size 3): color of goal nodes
|
Lua return values |
dwos (table of int): a table of handles of new drawing objects |
Python synopsis |
list dwos=simOMPL.drawPlannerData(string
taskHandle, float pointSize, float lineSize, list color, list
startColor, list goalColor)
|
See also
|
simOMPL.drawPath simOMPL.removeDrawingObjects
|
simOMPL.enforceBounds
simOMPL.getGoalDistance
simOMPL.getPath
simOMPL.getPathState
simOMPL.getPathStateCount
simOMPL.getPlannerData
Description
|
Get planner data for this motion planning task.
Data is represented as a graph. For each graph vertex, a
state and a tag are returned. A list of edges is returned as well, as
pairs of vertex indices, describing connectivity of vertices. Some
vertices are marked start or goal.
|
Lua synopsis |
float[] states, int[] tags, float[]
tagsReal, int[] edges, float[] edgeWeights, int[] startVertices, int[]
goalVertices=simOMPL.getPlannerData(string taskHandle)
|
Lua parameters |
|
Lua return values |
states (table of float): a table of states,
representing the configurations in the constructed search graph. States
are specified linearly.
tags (table of int): a table of tags (one integer for every vertex)
tagsReal (table of float): a table of tags (one float for every vertex)
edges (table of int): the pairs of vertex indices describing vertex connectivity
edgeWeights (table of float): the weight (cost) associated to each edge
startVertices (table of int): the indices of vertices marked 'start'
goalVertices (table of int): the indices of vertices marked 'goal'
|
Python synopsis |
list states, list tags, list tagsReal,
list edges, list edgeWeights, list startVertices, list
goalVertices=simOMPL.getPlannerData(string taskHandle)
|
See also
|
simOMPL.compute simOMPL.getGoalDistance simOMPL.getPath simOMPL.hasApproximateSolution simOMPL.hasExactSolution simOMPL.hasSolution simOMPL.interpolatePath simOMPL.setAlgorithm simOMPL.simplifyPath simOMPL.solve
|
simOMPL.getProjectedPathLength
simOMPL.getReversedPath
simOMPL.getStateSpaceDimension
simOMPL.hasApproximateSolution
simOMPL.hasExactSolution
simOMPL.hasSolution
simOMPL.interpolatePath
simOMPL.isStateValid
simOMPL.isStateWithinBounds
simOMPL.printTaskInfo
simOMPL.projectStates
simOMPL.projectionSize
simOMPL.readState
simOMPL.removeDrawingObjects
Description
|
remove the drawing objects created with related functions |
Lua synopsis |
simOMPL.removeDrawingObjects(string taskHandle, int[] dwos)
|
Lua parameters |
taskHandle (string): handle of the task
dwos (table of int): table of handles to drawing objects, as returned by the functions
|
Lua return values |
- |
Python synopsis |
simOMPL.removeDrawingObjects(string taskHandle, list dwos)
|
See also
|
simOMPL.drawPath simOMPL.drawPlannerData
|
simOMPL.setAlgorithm
simOMPL.setCollisionPairs
simOMPL.setDubinsParams
Description
|
Set extra state space parameters of a dubins state space. |
Lua synopsis |
simOMPL.setDubinsParams(string stateSpaceHandle, float turningRadius, bool isSymmetric)
|
Lua parameters |
stateSpaceHandle (string): handle to state space component
turningRadius (float): turning radius
isSymmetric (bool): true if it is symmetric, otherwise false
|
Lua return values |
- |
Python synopsis |
simOMPL.setDubinsParams(string stateSpaceHandle, float turningRadius, bool isSymmetric)
|
See also
|
simOMPL.createStateSpace simOMPL.destroyStateSpace simOMPL.getStateSpaceDimension simOMPL.setStateSpace
|
simOMPL.setGoal
Description
|
Set the goal for the specificed task object by a dummy pair.
One of the two dummies is part of the robot. The other dummy
is fixed in the environment. When the task is solved, the position or
pose of the two dummies will (approximatively) be the same. Dummy-dummy
distances are relative to an optional reference dummy, and are evaluated
using an optional metric
|
Lua synopsis |
simOMPL.setGoal(string taskHandle, int
robotDummy, int goalDummy, float tolerance=0.001f, float[] metric={1.0,
1.0, 1.0, 0.1}, int refDummy=-1)
|
Lua parameters |
robotDummy (int): a dummy attached to the robot
goalDummy (int): a dummy fixed in the environment, representing the goal pose/position
tolerance (float, default: 0.001f): tolerated dummy-dummy distance
metric (table of float, default: {1.0, 1.0, 1.0, 0.1}): a metric (x,y,z,angle) used to evaluate the dummy-dummy distance
refDummy (int, default: -1): an reference dummy, relative to which the metric will be used
|
Lua return values |
- |
Python synopsis |
simOMPL.setGoal(string taskHandle, int
robotDummy, int goalDummy, float tolerance=0.001f, list metric={1.0,
1.0, 1.0, 0.1}, int refDummy=-1)
|
See also
|
simOMPL.addGoalState simOMPL.createTask simOMPL.destroyTask simOMPL.printTaskInfo simOMPL.setAlgorithm simOMPL.setCollisionPairs simOMPL.setGoalCallback simOMPL.setGoalState simOMPL.setGoalStates simOMPL.setProjectionEvaluationCallback simOMPL.setStartState simOMPL.setStateSpace simOMPL.setStateValidationCallback simOMPL.setStateValidityCheckingResolution simOMPL.setValidStateSamplerCallback simOMPL.setVerboseLevel simOMPL.setup simOMPL.addGoalState simOMPL.setGoalCallback simOMPL.setGoalState simOMPL.setGoalStates
|
simOMPL.setGoalCallback
simOMPL.setGoalState
simOMPL.setGoalStates
simOMPL.setProjectionEvaluationCallback
simOMPL.setStartState
simOMPL.setStateSpace
simOMPL.setStateValidationCallback
simOMPL.setStateValidityCheckingResolution
simOMPL.setValidStateSamplerCallback
simOMPL.setVerboseLevel
simOMPL.setup
simOMPL.simplifyPath
simOMPL.solve
simOMPL.stateDistance
simOMPL.writeState
|