Python Bindings

By default, the Python bindings will be compiled for 2.7. In order to build for different versions of Python you can specify PYBIND_PYTHON_EXECUTABLE in the additional CMake arguments of your catkin workspace:

catkin config --cmake-args -DPYBIND_PYTHON_EXECUTABLE=/usr/bin/python3
class pyexotica.BaseType

Bases: pybind11_builtins.pybind11_object

Fixed = BaseType.Fixed
Floating = BaseType.Floating
Planar = BaseType.Planar
class pyexotica.CollisionProxy

Bases: pybind11_builtins.pybind11_object

Contact1
Contact2
Distance
Normal1
Normal2
Object1
Object2
Transform1
Transform2
class pyexotica.CollisionScene

Bases: pybind11_builtins.pybind11_object

alwaysExternallyUpdatedCollisionScene
continuousCollisionCheck(self: _pyexotica.CollisionScene, arg0: unicode, arg1: _pyexotica.KDLFrame, arg2: _pyexotica.KDLFrame, arg3: unicode, arg4: _pyexotica.KDLFrame, arg5: _pyexotica.KDLFrame) → _pyexotica.ContinuousCollisionProxy
replaceCylindersWithCapsules
replacePrimitiveShapesWithMeshes
robotLinkPadding
robotLinkScale
updateCollisionObjectTransforms(self: _pyexotica.CollisionScene) → None
worldLinkPadding
worldLinkScale
class pyexotica.ContinuousCollisionProxy

Bases: pybind11_builtins.pybind11_object

ContactTransform1
ContactTransform2
InCollision
Object1
Object2
TimeOfContact
Transform1
Transform2
class pyexotica.EndPoseTask

Bases: pybind11_builtins.pybind11_object

J
JN
NumTasks
Phi
PhiN
S
TaskMaps
Tasks
y
ydiff
class pyexotica.KDLFrame

Bases: pybind11_builtins.pybind11_object

getAngleAxis(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, 1]]
getFrame(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, n]]
getQuaternion(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, 1]]
getRPY(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, 1]]
getTranslation(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[3, 1]]
getTranslationAndAngleAxis(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, 1]]
getTranslationAndQuaternion(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, 1]]
getTranslationAndRPY(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, 1]]
getTranslationAndZYX(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, 1]]
getTranslationAndZYZ(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, 1]]
getZYX(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, 1]]
getZYZ(self: _pyexotica.KDLFrame) → numpy.ndarray[float64[m, 1]]
inverse(self: _pyexotica.KDLFrame) → _pyexotica.KDLFrame
class pyexotica.MotionSolver

Bases: _pyexotica.Object

getPlanningTime(self: _pyexotica.MotionSolver) → float
getProblem(self: _pyexotica.MotionSolver) → exotica::PlanningProblem
maxIterations
solve(self: _pyexotica.MotionSolver) → numpy.ndarray[float64[m, n]]

Solve the problem

specifyProblem(self: _pyexotica.MotionSolver, planningProblem: exotica::PlanningProblem) → None

Assign problem to the solver

class pyexotica.Object

Bases: pybind11_builtins.pybind11_object

debugMode
getName(self: _pyexotica.Object) → unicode

Object name

getType(self: _pyexotica.Object) → unicode

Object type

namespace
class pyexotica.PlanningProblem

Bases: _pyexotica.Object

getCostEvolution(self: _pyexotica.PlanningProblem) → Tuple[List[float], List[float]]
getNumberOfProblemUpdates(self: _pyexotica.PlanningProblem) → int
getScene(self: _pyexotica.PlanningProblem) → exotica::Scene
getTasks(self: _pyexotica.PlanningProblem) → List[_pyexotica.TaskMap]
isValid(self: _pyexotica.PlanningProblem) → bool
resetNumberOfProblemUpdates(self: _pyexotica.PlanningProblem) → None
startState
startTime
class pyexotica.RotationType

Bases: pybind11_builtins.pybind11_object

AngleAxis = RotationType.AngleAxis
Matrix = RotationType.Matrix
Quaternion = RotationType.Quaternion
RPY = RotationType.RPY
ZYX = RotationType.ZYX
ZYZ = RotationType.ZYZ
class pyexotica.SamplingTask

Bases: pybind11_builtins.pybind11_object

JN
NumTasks
Phi
PhiN
S
TaskMaps
Tasks
y
ydiff
class pyexotica.Scene

Bases: _pyexotica.Object

Update(self: _pyexotica.Scene, x: numpy.ndarray[float64[m, 1]], t: float=0.0) → None
addObject(self: _pyexotica.Scene, name: unicode, transform: _pyexotica.KDLFrame=KDL::Frame ([0.000000 0.000000 0.000000] [0.000000 0.000000 0.000000 1.000000]), parent: unicode=u'', shapeResourcePath: unicode, scale: numpy.ndarray[float64[3, 1]]=array([ 1., 1., 1.]), updateCollisionScene: bool=True) → None
addTrajectory(self: _pyexotica.Scene, arg0: unicode, arg1: unicode) → None
addTrajectoryFromFile(self: _pyexotica.Scene, arg0: unicode, arg1: unicode) → None
attachObject(self: _pyexotica.Scene, arg0: unicode, arg1: unicode) → None
attachObjectLocal(self: _pyexotica.Scene, arg0: unicode, arg1: unicode, arg2: _pyexotica.KDLFrame) → None
cleanScene(self: _pyexotica.Scene) → None
controlledLinkToCollisionLinkMap
detachObject(self: _pyexotica.Scene, arg0: unicode) → None
fk(*args, **kwargs)

Overloaded function.

  1. fk(self: _pyexotica.Scene, arg0: unicode, arg1: _pyexotica.KDLFrame, arg2: unicode, arg3: _pyexotica.KDLFrame) -> _pyexotica.KDLFrame
  2. fk(self: _pyexotica.Scene, arg0: unicode, arg1: unicode) -> _pyexotica.KDLFrame
  3. fk(self: _pyexotica.Scene, arg0: unicode) -> _pyexotica.KDLFrame
getBaseType(self: _pyexotica.Scene) → _pyexotica.BaseType
getCollisionDistance(*args, **kwargs)

Overloaded function.

  1. getCollisionDistance(self: _pyexotica.Scene, self: bool=True) -> List[_pyexotica.CollisionProxy]
  2. getCollisionDistance(self: _pyexotica.Scene, Object1: unicode, Object2: unicode) -> List[_pyexotica.CollisionProxy]
  3. getCollisionDistance(self: _pyexotica.Scene, Object1: unicode, self: bool=True) -> List[_pyexotica.CollisionProxy]
  4. getCollisionDistance(self: _pyexotica.Scene, objects: List[unicode], self: bool=True) -> List[_pyexotica.CollisionProxy]
getCollisionScene(self: _pyexotica.Scene) → exotica::CollisionScene
getControlledLinkNames(self: _pyexotica.Scene) → List[unicode]
getControlledState(self: _pyexotica.Scene) → numpy.ndarray[float64[m, 1]]
getGroupName(self: _pyexotica.Scene) → unicode
getJointNames(self: _pyexotica.Scene) → List[unicode]
getModelJointNames(self: _pyexotica.Scene) → List[unicode]
getModelLinkNames(self: _pyexotica.Scene) → List[unicode]
getModelRootLinkName(self: _pyexotica.Scene) → unicode
getModelState(self: _pyexotica.Scene) → numpy.ndarray[float64[m, 1]]
getModelStateMap(self: _pyexotica.Scene) → Dict[unicode, float]
getRootFrameName(self: _pyexotica.Scene) → unicode
getRootJointName(self: _pyexotica.Scene) → unicode
getScene(self: _pyexotica.Scene) → unicode
getSolver(self: _pyexotica.Scene) → exotica::KinematicTree
getTrajectory(self: _pyexotica.Scene, arg0: unicode) → unicode
hasAttachedObject(self: _pyexotica.Scene, arg0: unicode) → bool
isCollisionFree(self: _pyexotica.Scene, Object1: unicode, Object2: unicode, SafeDistance: float=0.0) → bool
isStateValid(self: _pyexotica.Scene, self: bool=True, SafeDistance: float=0.0) → bool
jacobian(*args, **kwargs)

Overloaded function.

  1. jacobian(self: _pyexotica.Scene, arg0: unicode, arg1: _pyexotica.KDLFrame, arg2: unicode, arg3: _pyexotica.KDLFrame) -> numpy.ndarray[float64[m, n]]
  2. jacobian(self: _pyexotica.Scene, arg0: unicode, arg1: unicode) -> numpy.ndarray[float64[m, n]]
  3. jacobian(self: _pyexotica.Scene, arg0: unicode) -> numpy.ndarray[float64[m, n]]
loadScene(self: _pyexotica.Scene, sceneString: unicode, offsetTransform: _pyexotica.KDLFrame=KDL::Frame ([0.000000 0.000000 0.000000] [0.000000 0.000000 0.000000 1.000000]), updateCollisionScene: bool=True) → None
loadSceneFile(self: _pyexotica.Scene, fileName: unicode, offsetTransform: _pyexotica.KDLFrame=KDL::Frame ([0.000000 0.000000 0.000000] [0.000000 0.000000 0.000000 1.000000]), updateCollisionScene: bool=True) → None
modelLinkToCollisionLinkMap
publishProxies(self: _pyexotica.Scene, arg0: List[_pyexotica.CollisionProxy]) → None
publishScene(self: _pyexotica.Scene) → None
removeObject(self: _pyexotica.Scene, arg0: unicode) → None
removeTrajectory(self: _pyexotica.Scene, arg0: unicode) → None
setCollisionScene(self: _pyexotica.Scene, arg0: genpy.Message) → None
setModelState(self: _pyexotica.Scene, x: numpy.ndarray[float64[m, 1]], t: float=0.0, updateTrajectory: bool=False) → None
setModelStateMap(self: _pyexotica.Scene, x: Dict[unicode, float], t: float=0.0, updateTrajectory: bool=False) → None
updateCollisionObjects(self: _pyexotica.Scene) → None
updateSceneFrames(self: _pyexotica.Scene) → None
updateWorld(self: _pyexotica.Scene, arg0: genpy.Message) → None
class pyexotica.Setup

Bases: pybind11_builtins.pybind11_object

createMap(arg0: Initializer) → exotica::TaskMap
createProblem(arg0: Initializer) → exotica::PlanningProblem
createSolver(arg0: Initializer) → exotica::MotionSolver
getCollisionScenes() → List[unicode]

Returns a list of available collision scene plug-ins.

getInitializers() → List[Initializer]

Returns a list of available initializers with all available parameters/arguments.

getMaps() → List[unicode]

Returns a list of available task maps.

getPackagePath(arg0: unicode) → unicode

ROS package path resolution.

getProblems() → List[unicode]

Returns a list of available problems.

getSolvers() → List[unicode]

Returns a list of available solvers.

initRos(name: unicode=u'exotica', anonymous: bool=False) → None

Initializes an internal ROS node for publishing debug information from Exotica (i.e., activates ROS features). Options are setting the name and whether to spawn an anonymous node.

loadProblem(filepath: unicode) → exotica::PlanningProblem

Instantiate only a problem from an XML file containing solely a problem initializer.

loadSolver(filepath: unicode) → exotica::MotionSolver

Instantiate solver and problem from an XML file containing both a solver and problem initializer.

loadSolverStandalone(filepath: unicode) → exotica::MotionSolver

Instantiate only a solver from an XML file containing solely a solver initializer.

printSupportedClasses() → None

Print a list of available plug-ins sorted by class.

class pyexotica.ShapeType

Bases: pybind11_builtins.pybind11_object

Box = ShapeType.Box
Cone = ShapeType.Cone
Cylinder = ShapeType.Cylinder
Mesh = ShapeType.Mesh
Octree = ShapeType.Octree
Plane = ShapeType.Plane
Sphere = ShapeType.Sphere
UnknownShape = ShapeType.UnknownShape
class pyexotica.TaskMap

Bases: _pyexotica.Object

debug(self: _pyexotica.TaskMap) → None
id
length
lengthJ
start
startJ
taskSpaceDim(self: _pyexotica.TaskMap) → int
taskSpaceJacobianDim(self: _pyexotica.TaskMap) → int
class pyexotica.TaskSpaceVector

Bases: pybind11_builtins.pybind11_object

data
setZero(self: _pyexotica.TaskSpaceVector, arg0: int) → None
class pyexotica.TerminationCriterion

Bases: pybind11_builtins.pybind11_object

BacktrackIterationLimit = TerminationCriterion.BacktrackIterationLimit
Divergence = TerminationCriterion.Divergence
FunctionTolerance = TerminationCriterion.FunctionTolerance
GradientTolerance = TerminationCriterion.GradientTolerance
IterationLimit = TerminationCriterion.IterationLimit
NotStarted = TerminationCriterion.NotStarted
StepTolerance = TerminationCriterion.StepTolerance
UserDefined = TerminationCriterion.UserDefined
class pyexotica.TimeIndexedTask

Bases: pybind11_builtins.pybind11_object

J
JN
NumTasks
Phi
PhiN
S
T
TaskMaps
Tasks
y
ydiff
class pyexotica.Timer

Bases: pybind11_builtins.pybind11_object

getDuration(self: _pyexotica.Timer) → float
reset(self: _pyexotica.Timer) → None

Exotica wrapper of OMPL solvers

class ompl_solver_py.BKPIECE

Bases: ompl_solver_py.OMPLMotionSolver

class ompl_solver_py.EST

Bases: ompl_solver_py.OMPLMotionSolver

class ompl_solver_py.KPIECE

Bases: ompl_solver_py.OMPLMotionSolver

class ompl_solver_py.LazyPRM

Bases: ompl_solver_py.OMPLMotionSolver

clear(self: ompl_solver_py.LazyPRM) → None
clearQuery(self: ompl_solver_py.LazyPRM) → None
edgeCount(self: ompl_solver_py.LazyPRM) → int
milestoneCount(self: ompl_solver_py.LazyPRM) → int
multiQuery
setup(self: ompl_solver_py.LazyPRM) → None
class ompl_solver_py.OMPLMotionSolver

Bases: _pyexotica.MotionSolver

getLongestValidSegmentLength(self: ompl_solver_py.OMPLMotionSolver) → float
getMaximumExtent(self: ompl_solver_py.OMPLMotionSolver) → float
getRandomSeed(self: ompl_solver_py.OMPLMotionSolver) → int
getValidSegmentCountFactor(self: ompl_solver_py.OMPLMotionSolver) → int
setLongestValidSegmentFraction(self: ompl_solver_py.OMPLMotionSolver, arg0: float) → None
setValidSegmentCountFactor(self: ompl_solver_py.OMPLMotionSolver, arg0: int) → None
class ompl_solver_py.PRM

Bases: ompl_solver_py.OMPLMotionSolver

clear(self: ompl_solver_py.PRM) → None
clearQuery(self: ompl_solver_py.PRM) → None
edgeCount(self: ompl_solver_py.PRM) → int
expandRoadmap(self: ompl_solver_py.PRM, arg0: float) → None
growRoadmap(self: ompl_solver_py.PRM, arg0: float) → None
milestoneCount(self: ompl_solver_py.PRM) → int
multiQuery
setup(self: ompl_solver_py.PRM) → None
class ompl_solver_py.RRT

Bases: ompl_solver_py.OMPLMotionSolver

class ompl_solver_py.RRTConnect

Bases: ompl_solver_py.OMPLMotionSolver

getRange(self: ompl_solver_py.RRTConnect) → float
setRange(self: ompl_solver_py.RRTConnect, arg0: float) → None